32 #include "generated/airframe.h"
41 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
42 #define STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER 0
44 #if STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
45 #ifndef RPM_PWM_CHANNEL
46 #error notch filter requires module rpm_sensor.xml
49 #endif // USE_NOTCHFILTER
52 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_ROLL
53 #define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_ROLL 4.5
55 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_PITCH
56 #define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_PITCH 0
58 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_ROLL_P
59 #define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_P 12
61 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_PITCH_P
62 #define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_P 8
64 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_YAW_P
65 #define STABILIZATION_ATTITUDE_HELI_INDI_YAW_P 10
67 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_YAW_D
68 #define STABILIZATION_ATTITUDE_HELI_INDI_YAW_D 30
70 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_GINV_ROLL_TO_ROLL
71 #define STABILIZATION_ATTITUDE_HELI_INDI_GINV_ROLL_TO_ROLL 11681
73 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_GINV_PITCH_TO_PITCH
74 #define STABILIZATION_ATTITUDE_HELI_INDI_GINV_PITCH_TO_PITCH 13873
76 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_GINV_YAW_TO_YAW
77 #define STABILIZATION_ATTITUDE_HELI_INDI_GINV_YAW_TO_YAW 730
79 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_ROLL_COMMAND_ROTATION
80 #define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_COMMAND_ROTATION 11.0
82 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_PITCH_COMMAND_ROTATION
83 #define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_COMMAND_ROTATION -30.0
85 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
86 #define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT 10.0
88 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_ROLL
89 #define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_ROLL STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
91 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_PITCH
92 #define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_PITCH STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
94 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_YAW
95 #define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_YAW STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
97 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_THRUST
98 #define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_THRUST STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
100 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
101 #define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT 40.0
103 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_ROLL
104 #define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_ROLL STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
106 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_PITCH
107 #define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_PITCH STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
109 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_YAW
110 #define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_YAW STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
112 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_THRUST
113 #define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_THRUST STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
115 #ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCH_MIN_RPM
116 #define STABILIZATION_ATTITUDE_HELI_INDI_NOTCH_MIN_RPM 1500
118 #define INDI_NOTCH_MIN_RPM STABILIZATION_ATTITUDE_HELI_INDI_NOTCH_MIN_RPM
121 #define INVG_00 STABILIZATION_ATTITUDE_HELI_INDI_GINV_ROLL_TO_ROLL
122 #define INVG_11 STABILIZATION_ATTITUDE_HELI_INDI_GINV_PITCH_TO_PITCH
123 #define INVG_22 STABILIZATION_ATTITUDE_HELI_INDI_GINV_YAW_TO_YAW
124 #define INVG_33 -50000 // Not used at the moment
125 #define INT32_INVG_FRAC 16
150 #if STABILIZATION_ATTITUDE_HELI_INDI_USE_FAST_DYN_FILTERS
160 #if PERIODIC_TELEMETRY
165 #endif // PERIODIC_TELEMETRY
187 #if STABILIZATION_ATTITUDE_HELI_INDI_USE_FAST_DYN_FILTERS
216 _out[
INDI_YAW] = yaw_output_buffer[buf_idx];
217 yaw_output_buffer[buf_idx] = _in[
INDI_YAW];
229 static int32_t prev_thrust_out = 0;
348 #if STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
375 (PERIODIC_FREQUENCY + 13);
413 #if STABILIZATION_ATTITUDE_HELI_INDI_USE_FAST_DYN_FILTERS
416 STABILIZATION_ATTITUDE_HELI_INDI_FAST_DYN_ROLL_BW, 0,
MAX_PPRZ, PERIODIC_FREQUENCY);
418 STABILIZATION_ATTITUDE_HELI_INDI_FAST_DYN_PITCH_BW, 0,
MAX_PPRZ, PERIODIC_FREQUENCY);
429 #if PERIODIC_TELEMETRY
443 ltp_accel.
x = ltp_accel_nedcoor->
x;
444 ltp_accel.
y = ltp_accel_nedcoor->
y;
445 ltp_accel.
z = ltp_accel_nedcoor->
z;
473 #if STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
502 static int32_t previous_filt_yawrate = 0;
504 previous_filt_yawrate);
508 int32_t roll_virtual_control = (heli_indi_gains.
roll_p * att_err.
qx) / 4;
512 int32_t yaw_rate_reference = (heli_indi_gains.
yaw_p * att_err.
qz / 8);
513 int32_t yaw_virtual_control = heli_indi_gains.
yaw_d * (yaw_rate_reference - body_rate->
r);
609 #if USE_EARTH_BOUND_RC_SETPOINT
int16_t motor_rpm
RPM of the main motor.
int32_t psi
in rad with INT32_ANGLE_FRAC
#define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_P
static void delayed_first_order_lowpass_initialize(struct delayed_first_order_lowpass_filter_t *f, uint32_t omega, uint8_t delay, uint16_t max_inc, uint16_t sample_frequency)
delayed_first_order_lowpass_initialize
int32_t filtered_measurement[INDI_NR_FILTERS][INDI_DOF]
Filtered measurement.
int32_t error[INDI_DOF]
virtual control minus measurement
static int32_t delayed_first_order_lowpass_propagate(struct delayed_first_order_lowpass_filter_t *f, int32_t input)
delayed_first_order_lowpass_propagate
void stabilization_attitude_read_rc_setpoint_quat_f(struct FloatQuat *q_sp, bool in_flight, bool in_carefree, bool coordinated_turn)
Read attitude setpoint from RC as quaternion Interprets the stick positions as axes.
static void int32_quat_normalize(struct Int32Quat *q)
normalize a quaternion inplace
void stabilization_attitude_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t heading)
static void notch_filter_init(struct SecondOrderNotchFilter *filter, float cutoff_frequency, float bandwidth, uint16_t sample_frequency)
Initialize second order notch filter.
void stabilization_attitude_heli_indi_set_steadystate_roll(float roll)
stabilization_attitude_heli_indi_set_steadystate_roll
void int32_quat_inv_comp(struct Int32Quat *b2c, struct Int32Quat *a2b, struct Int32Quat *a2c)
Composition (multiplication) of two quaternions.
Simple matrix helper macros.
int32_t command_out[2][INDI_DOF]
Command and command from previous measurement.
static void indi_apply_actuator_models(int32_t _out[], int32_t _in[])
void stabilization_attitude_init(void)
stabilization_attitude_init
Periodic telemetry system header (includes downlink utility and generated code).
static struct Int32RMat * stateGetNedToBodyRMat_i(void)
Get vehicle body attitude rotation matrix (int).
General attitude stabilization interface for rotorcrafts.
bool autopilot_get_motors_on(void)
get motors status
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_YAW
int32_t theta
in rad with INT32_ANGLE_FRAC
void int32_quat_of_eulers(struct Int32Quat *q, struct Int32Eulers *e)
Quaternion from Euler angles.
Simple first order low pass filter with bilinear transform.
int32_t stabilization_attitude_get_heading_i(void)
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_YAW
void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
#define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_COMMAND_ROTATION
Read an attitude setpoint from the RC.
struct HeliIndiGains heli_indi_gains
#define DELAYED_FIRST_ORDER_LOWPASS_FILTER_FILTER_ALPHA_SHIFT
#define INDI_YAW_BUFFER_SIZE
int32_t invG[INDI_DOF][INDI_DOF]
Inverse control effectiveness matrix.
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_THRUST
void indi_apply_actuator_notch_filters(int32_t _out[], int32_t _in[])
static void int32_vect_sum(int32_t *o, const int32_t *a, const int32_t *b, const int n)
o = a + b
static void init_butterworth_2_low_pass_int(Butterworth2LowPass_int *filter, float cut_off, float sample_time, int32_t value)
Init a second order Butterworth filter.
struct Int32Quat sp_offset
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_ROLL
#define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_PITCH
static struct Int32Quat * stateGetNedToBodyQuat_i(void)
Get vehicle body attitude quaternion (int).
struct Int32Quat stab_att_sp_quat
with INT32_QUAT_FRAC
void(* apply_actuator_filters[INDI_NR_FILTERS])(int32_t _out[], int32_t _in[])
int32_t actuator_out[INDI_DOF]
Actuator position.
void stabilization_attitude_read_rc_setpoint_quat_earth_bound_f(struct FloatQuat *q_sp, bool in_flight, bool in_carefree, bool coordinated_turn)
void(* apply_compensator_filters)(int32_t _out[], int32_t _in[])
int32_t r
in rad/s with INT32_RATE_FRAC
#define PPRZ_ITRIG_SIN(_s, _a)
#define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_P
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_THRUST
int32_t roll_comp_angle
Angle to rotate pitch/roll commands with INT32_ANGLE_FRAC.
#define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_ROLL
void indi_apply_measurement_butterworth_filters(int32_t _out[], int32_t _in[])
static struct Int32Rates * stateGetBodyRates_i(void)
Get vehicle body angular rate (int).
void int32_rmat_vmult(struct Int32Vect3 *vb, struct Int32RMat *m_a2b, struct Int32Vect3 *va)
rotate 3D vector by rotation matrix.
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_ROLL
int32_t filtered_actuator[INDI_NR_FILTERS][INDI_DOF]
Filtered actuator position.
void stabilization_attitude_enter(void)
float sp_offset_pitch
Neutral pitch angle [deg].
Paparazzi floating point algebra.
int32_t reference[INDI_DOF]
Range -MAX_PPRZ:MAX_PPRZ.
static void indi_apply_compensator_filters(int32_t _out[], int32_t _in[])
The main idea of this function is to slow down a certain actuator, so that the actuator dynamics filt...
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_PITCH
void stabilization_attitude_set_failsafe_setpoint(void)
struct Int32Eulers stab_att_sp_euler
with INT32_ANGLE_FRAC
struct SecondOrderNotchFilter measurement_notchfilter[INDI_DOF]
#define QUAT_BFP_OF_REAL(_qi, _qf)
void stabilization_attitude_heli_indi_set_steadystate_pitch(float pitch)
stabilization_attitude_heli_indi_set_steadystate_pitch
void indi_apply_measurement_notch_filters(int32_t _out[], int32_t _in[])
float sp_offset_roll
Neutral roll angle [deg].
#define STABILIZATION_ATTITUDE_HELI_INDI_YAW_P
Butterworth2LowPass_int measurement_lowpass_filters[INDI_DOF]
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_PITCH
void stabilization_attitude_set_rpy_setpoint_i(struct Int32Eulers *rpy)
static int32_t update_butterworth_2_low_pass_int(Butterworth2LowPass_int *filter, int32_t value)
Update second order Butterworth low pass filter state with a new value(fixed point version)...
void int32_quat_comp_inv(struct Int32Quat *a2b, struct Int32Quat *a2c, struct Int32Quat *b2c)
Composition (multiplication) of two quaternions.
bool enable_notch
Use notch filters.
#define MAT_MUL_VECT(_n, o, a, b)
o = a * b
static void indi_apply_notch_filters(struct SecondOrderNotchFilter *filter, int32_t _out[], int32_t _in[])
#define ANGLE_BFP_OF_REAL(_af)
Core autopilot interface common to all firmwares.
int32_t du[INDI_DOF]
Actuator commanded increment.
static void notch_filter_set_filter_frequency(struct SecondOrderNotchFilter *filter, float frequency)
Set notch filter frequency in Hz.
static void notch_filter_update(struct SecondOrderNotchFilter *filter, int32_t *input_signal, int32_t *output_signal)
Notch filter propagate.
void stabilization_attitude_run(bool in_flight)
Butterworth2LowPass_int actuator_lowpass_filters[INDI_DOF]
int32_t phi
in rad with INT32_ANGLE_FRAC
int32_t pprz_itrig_sin(int32_t angle)
API to get/set the generic vehicle states.
struct IndiController_int heli_indi_ctl
vector in North East Down coordinates
int32_t buffer[DELAYED_FIRST_ORDER_LOWPASS_FILTER_BUFFER_SIZE]
void float_quat_of_orientation_vect(struct FloatQuat *q, const struct FloatVect3 *ov)
Quaternion from orientation vector.
void(* apply_measurement_filters[INDI_NR_FILTERS])(int32_t _out[], int32_t _in[])
int32_t measurement[INDI_DOF]
Raw measurement.
static void int32_quat_wrap_shortest(struct Int32Quat *q)
static void int32_vect_diff(int32_t *o, const int32_t *a, const int32_t *b, const int n)
o = a - b
int32_t stabilization_cmd[COMMANDS_NB]
Stabilization commands.
int32_t p
in rad/s with INT32_RATE_FRAC
uint16_t rpm_sensor_get_rpm(void)
int32_t pitch_comp_angle
Angle to rotate pitch/roll commands with INT32_ANGLE_FRAC.
#define INDI_NOTCH_MIN_RPM
static void int32_vect_copy(int32_t *a, const int32_t *b, const int n)
a = b
#define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_COMMAND_ROTATION
struct SecondOrderNotchFilter actuator_notchfilter[INDI_DOF]
void indi_apply_actuator_butterworth_filters(int32_t _out[], int32_t _in[])
void(* apply_actuator_models)(int32_t _out[], int32_t _in[])
static struct Int32Eulers * stateGetNedToBodyEulers_i(void)
Get vehicle body attitude euler angles (int).
int32_t pprz_itrig_cos(int32_t angle)
void stabilization_attitude_heli_indi_set_steadystate_pitchroll()
stabilization_attitude_heli_indi_set_steadystate_pitchroll
int32_t q
in rad/s with INT32_RATE_FRAC
#define STABILIZATION_ATTITUDE_HELI_INDI_YAW_D
struct delayed_first_order_lowpass_filter_t actuator_model[INDI_DOF]
static struct NedCoor_i * stateGetAccelNed_i(void)
Get acceleration in NED coordinates (int).
int32_t u_setpoint[INDI_DOF]
Actuator setpoint without compensator.
#define PPRZ_ITRIG_COS(_c, _a)
Paparazzi fixed point algebra.