Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
stabilization_attitude_heli_indi.c
Go to the documentation of this file.
1/*
2 * Copyright (c) 2016 Bart Slinger <bartslinger@gmail.com>
3 * Copyright (C) 2008-2009 Antoine Drouin <poinix@gmail.com>
4 *
5 * This file is part of paparazzi.
6 *
7 * paparazzi is free software; you can redistribute it and/or modify
8 * it under the terms of the GNU General Public License as published by
9 * the Free Software Foundation; either version 2, or (at your option)
10 * any later version.
11 *
12 * paparazzi is distributed in the hope that it will be useful,
13 * but WITHOUT ANY WARRANTY; without even the implied warranty of
14 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 * GNU General Public License for more details.
16 *
17 * You should have received a copy of the GNU General Public License
18 * along with paparazzi; see the file COPYING. If not, write to
19 * the Free Software Foundation, 59 Temple Place - Suite 330,
20 * Boston, MA 02111-1307, USA.
21 */
22
27#include "paparazzi.h"
31#include "state.h"
32#include "generated/airframe.h"
33#include "autopilot.h"
34
38
39#ifndef STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
40#define STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER 0
41#endif
42#if STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
43#ifndef RPM_PWM_CHANNEL
44#error notch filter requires module rpm_sensor.xml
45#endif
47#endif // USE_NOTCHFILTER
48
49/* Setup of all default values, these are configured for walkera genius cp v2 */
50#ifndef STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_ROLL
51#define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_ROLL 4.5
52#endif
53#ifndef STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_PITCH
54#define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_PITCH 0
55#endif
56#ifndef STABILIZATION_ATTITUDE_HELI_INDI_ROLL_P
57#define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_P 12
58#endif
59#ifndef STABILIZATION_ATTITUDE_HELI_INDI_PITCH_P
60#define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_P 8
61#endif
62#ifndef STABILIZATION_ATTITUDE_HELI_INDI_YAW_P
63#define STABILIZATION_ATTITUDE_HELI_INDI_YAW_P 10
64#endif
65#ifndef STABILIZATION_ATTITUDE_HELI_INDI_YAW_D
66#define STABILIZATION_ATTITUDE_HELI_INDI_YAW_D 30
67#endif
68#ifndef STABILIZATION_ATTITUDE_HELI_INDI_GINV_ROLL_TO_ROLL
69#define STABILIZATION_ATTITUDE_HELI_INDI_GINV_ROLL_TO_ROLL 11681
70#endif
71#ifndef STABILIZATION_ATTITUDE_HELI_INDI_GINV_PITCH_TO_PITCH
72#define STABILIZATION_ATTITUDE_HELI_INDI_GINV_PITCH_TO_PITCH 13873
73#endif
74#ifndef STABILIZATION_ATTITUDE_HELI_INDI_GINV_YAW_TO_YAW
75#define STABILIZATION_ATTITUDE_HELI_INDI_GINV_YAW_TO_YAW 730
76#endif
77#ifndef STABILIZATION_ATTITUDE_HELI_INDI_ROLL_COMMAND_ROTATION
78#define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_COMMAND_ROTATION 11.0
79#endif
80#ifndef STABILIZATION_ATTITUDE_HELI_INDI_PITCH_COMMAND_ROTATION
81#define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_COMMAND_ROTATION -30.0
82#endif
83#ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
84#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT 10.0
85#endif
86#ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_ROLL
87#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_ROLL STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
88#endif
89#ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_PITCH
90#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_PITCH STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
91#endif
92#ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_YAW
93#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_YAW STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
94#endif
95#ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_THRUST
96#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_THRUST STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_DEFAULT
97#endif
98#ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
99#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT 40.0
100#endif
101#ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_ROLL
102#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_ROLL STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
103#endif
104#ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_PITCH
105#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_PITCH STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
106#endif
107#ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_YAW
108#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_YAW STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
109#endif
110#ifndef STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_THRUST
111#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_THRUST STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_DEFAULT
112#endif
113#ifndef STABILIZATION_ATTITUDE_HELI_INDI_NOTCH_MIN_RPM
114#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCH_MIN_RPM 1500
115#endif
116#define INDI_NOTCH_MIN_RPM STABILIZATION_ATTITUDE_HELI_INDI_NOTCH_MIN_RPM
117
118/* Shorter defines to use lateron in the matrix */
119#define INVG_00 STABILIZATION_ATTITUDE_HELI_INDI_GINV_ROLL_TO_ROLL
120#define INVG_11 STABILIZATION_ATTITUDE_HELI_INDI_GINV_PITCH_TO_PITCH
121#define INVG_22 STABILIZATION_ATTITUDE_HELI_INDI_GINV_YAW_TO_YAW
122#define INVG_33 -50000 // Not used at the moment
123#define INT32_INVG_FRAC 16
124
127static struct Int32Quat sp_offset; // non-zero neutral attitude
128
135
136/* Main controller struct */
138
139/* Filter functions */
141int32_t alpha_yaw_inc; // Tail model parameters for spinning up
142int32_t alpha_yaw_dec; // Tail model parameters for spinning down
143/* Measurement filters */
148#if STABILIZATION_ATTITUDE_HELI_INDI_USE_FAST_DYN_FILTERS
149struct delayed_first_order_lowpass_filter_t fast_dynamics_model[2]; // only pitch and roll
150#endif
151
152/* Private functions declarations */
157
158
160{
165
166 /* Depending on yaw direction, change filter coefficient */
168 if (_in[INDI_YAW] - prev > 0) {
169 // Tail spinning up
171 } else {
172 // Tail spinning down
174 }
176
178
179#if STABILIZATION_ATTITUDE_HELI_INDI_USE_FAST_DYN_FILTERS
180 /* Also apply first order filter that represents fast damping dynamics in pitch and roll rate */
183#else
186#endif
187}
188
199{
202
203 /* Delay the tail by 9 samples */
205 static uint8_t buf_idx = 0;
206
207 buf_idx %= (INDI_YAW_BUFFER_SIZE - 1);
208 _out[INDI_YAW] = yaw_output_buffer[buf_idx];
209 yaw_output_buffer[buf_idx] = _in[INDI_YAW];
210 buf_idx++;
211
212 // Disregard, just use input:
214
215 /* Thrust compensated for slow tail dynamics:
216 * Step 1. What would be the next output of the system if the thrust cmd would be applied to the tail dynamics?
217 * Step 2. What input is required to obtain this output when assuming dynamics of thrust actuator?
218 *
219 * We can re-use alpha_yaw_dec and alpha_yaw_inc
220 */
221 static int32_t prev_thrust_out = 0;
223 if (_in[INDI_THRUST] - prev_thrust_out > 0) {
225 } else {
227 }
230
231 /* Now the target output is known, the collective dynamics is known. What input is required? */
236
237 /* At the moment, thrust is not fully implemented */
238 //_out[INDI_THRUST] = _in[INDI_THRUST];
239}
240
259
264
269
276
283
295
308
316{
317 /* Pitch roll setpoint not zero, because then helicopter drifts sideways */
318 /* orientation vector describing simultaneous rotation of roll/pitch */
319 struct FloatVect3 ov;
320 struct FloatQuat q;
321 ov.x = -heli_indi_ctl.sp_offset_roll * M_PI / 180;
322 ov.y = -heli_indi_ctl.sp_offset_pitch * M_PI / 180;
323 ov.z = 0.0;
324 /* quaternion from that orientation vector */
327}
328
335{
336 /* Initialization code INDI */
340#if STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
341 c->enable_notch = TRUE;
342#else
343 c->enable_notch = FALSE;
344#endif
345 c->motor_rpm = 0;
346
347 /* Set steady-state pitch and roll values */
351
352 /* Initialize inv(G) */
353 c->invG[0][0] = INVG_00; c->invG[0][1] = 0; c->invG[0][2] = 0; c->invG[0][3] = 0;
354 c->invG[1][0] = 0; c->invG[1][1] = INVG_11; c->invG[1][2] = 0; c->invG[1][3] = 0;
355 c->invG[2][0] = 0; c->invG[2][1] = 0; c->invG[2][2] = INVG_22; c->invG[2][3] = 0;
356 c->invG[3][0] = 0; c->invG[3][1] = 0; c->invG[3][2] = 0; c->invG[3][3] = INVG_33;
357
358 /* Actuator filter initialization */
363 PERIODIC_FREQUENCY); /* 450 because dynamic range is only 0-9600 */
364 /* Different dynamics for up and down */
367 (PERIODIC_FREQUENCY + 13); // OMEGA_DOWN = 13 rad/s, shift = 14
368
369 /* Notch filter initialization, bandwidth in Hz */
386
387 /* Low pass filter initialization, cutoff frequency in Hz */
404
405#if STABILIZATION_ATTITUDE_HELI_INDI_USE_FAST_DYN_FILTERS
406 /* Fast dynamics in roll and pitch model */
411#endif
412
413 /* Assign filter functions: */
420}
421
422void stabilization_attitude_run(bool in_flight, struct StabilizationSetpoint *sp, struct ThrustSetpoint *thrust, int32_t *cmd)
423{
424 (void) in_flight; // unused variable
426
427 /* set setpoint */
430
431 /* calculate acceleration in body frame */
433 struct Int32Vect3 ltp_accel;
434 struct Int32Vect3 body_accel; // Acceleration measurement in body frame
435 ltp_accel.x = ltp_accel_nedcoor->x;
436 ltp_accel.y = ltp_accel_nedcoor->y;
437 ltp_accel.z = ltp_accel_nedcoor->z;
438 int32_rmat_vmult(&body_accel, stateGetNedToBodyRMat_i(), &ltp_accel);
439
440 /* attitude error */
441 struct Int32Quat att_err;
443
444 /* Add steady-state value to attitude setpoint, because heli has
445 * non-zero roll angle by default
446 */
447 struct Int32Quat corr_att_sp_quat; // Corrected attitude setpoint
449
451 /* wrap it in the shortest direction */
454
455 /* rate error (setpoint for rates = 0) */
456 struct Int32Rates *body_rate = stateGetBodyRates_i();
457
458 /* Inform INDI about the measurement */
459 c->measurement[INDI_ROLL] = body_rate->p;
460 c->measurement[INDI_PITCH] = body_rate->q;
461 c->measurement[INDI_YAW] = body_rate->r;
462 c->measurement[INDI_THRUST] = body_accel.z;
463
464 /* Get RPM measurement */
465#if STABILIZATION_ATTITUDE_HELI_INDI_USE_NOTCHFILTER
468 } else {
470 }
471#endif
472
473 /* Apply actuator dynamics model to previously commanded values
474 * input = actuator command in previous cycle
475 * output = actual actuator position right now
476 */
478
479 /* Apply a set of filters, both to the actuator and the measurement */
482 for (uint8_t i = 1; i < INDI_NR_FILTERS; i++) {
485 }
486
487 /* RADIO throttle stick value, for 4dof mode */
488 //int32_t accel_z_sp = (-1)*3*((guidance_v.rc_delta_t - MAX_PPRZ/2) << INT32_ACCEL_FRAC) / (MAX_PPRZ/2);
489 //accel_z_sp = ((accel_z_sp << INT32_TRIG_FRAC) / guidance_v.thrust_coeff);
490
491 /* Transform yaw into a delta yaw while keeping filtered yawrate (kinda hacky) */
496 previous_filt_yawrate); // = approximately yaw acceleration error
498
499 /* Obtain virtual control input with P controller on pitch and roll */
502
503 /* Yaw with cascaded PD-controller to generate virtual control */
506
507 /* Set INDI references */
511 //c->reference[INDI_THRUST] = accel_z_sp;
512
513 /* Subtract (filtered) measurement from reference to get the error */
515
516 /* Multiply error with inverse of actuator effectiveness, to get delta u (required increment in input) */
517 MAT_MUL_VECT(INDI_DOF, c->du, c->invG, c->error);
518
519 /* Bitshift back */
524
525 /* Take the current (filtered) actuator position and add the incremental value. */
527 //c->u_setpoint[INDI_THRUST] = stabilization.cmd[COMMAND_THRUST];
528
529 /* bound the result */
534
535 /* Apply a compensator to the actuator setpoint to obtain actuator command */
537
538 /* At the end, set 'previous' output to current output */
540
541 /* Two correction angles, don't rotate but just add.
542 * sin/cos = tan
543 */
550
551 /* Disable tail when not armed, because this thing goes crazy */
553 cmd[COMMAND_YAW] = 0;
554 }
555}
556
558{
559}
560
bool autopilot_get_motors_on(void)
get motors status
Definition autopilot.c:295
Core autopilot interface common to all firmwares.
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
static int32_t delayed_first_order_lowpass_propagate(struct delayed_first_order_lowpass_filter_t *f, int32_t input)
delayed_first_order_lowpass_propagate
int32_t buffer[DELAYED_FIRST_ORDER_LOWPASS_FILTER_BUFFER_SIZE]
#define DELAYED_FIRST_ORDER_LOWPASS_FILTER_FILTER_ALPHA_SHIFT
void float_quat_of_orientation_vect(struct FloatQuat *q, const struct FloatVect3 *ov)
Quaternion from orientation vector.
Roation quaternion.
#define QUAT_BFP_OF_REAL(_qi, _qf)
int32_t p
in rad/s with INT32_RATE_FRAC
int32_t r
in rad/s with INT32_RATE_FRAC
int32_t q
in rad/s with INT32_RATE_FRAC
static void int32_quat_normalize(struct Int32Quat *q)
normalize a quaternion inplace
static void int32_vect_sum(int32_t *o, const int32_t *a, const int32_t *b, const int n)
o = a + b
#define ANGLE_BFP_OF_REAL(_af)
void int32_quat_comp_inv(struct Int32Quat *a2b, struct Int32Quat *a2c, struct Int32Quat *b2c)
Composition (multiplication) of two quaternions.
void int32_rmat_vmult(struct Int32Vect3 *vb, struct Int32RMat *m_a2b, struct Int32Vect3 *va)
rotate 3D vector by rotation matrix.
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
static void int32_vect_copy(int32_t *a, const int32_t *b, const int n)
a = b
void int32_quat_inv_comp(struct Int32Quat *b2c, struct Int32Quat *a2b, struct Int32Quat *a2c)
Composition (multiplication) of two quaternions.
euler angles
Rotation quaternion.
angular rates
vector in North East Down coordinates
static struct NedCoor_i * stateGetAccelNed_i(void)
Get acceleration in NED coordinates (int).
Definition state.h:1177
static struct Int32Quat * stateGetNedToBodyQuat_i(void)
Get vehicle body attitude quaternion (int).
Definition state.h:1276
static struct Int32RMat * stateGetNedToBodyRMat_i(void)
Get vehicle body attitude rotation matrix (int).
Definition state.h:1282
static struct Int32Rates * stateGetBodyRates_i(void)
Get vehicle body angular rate (int).
Definition state.h:1358
Simple first order low pass filter with bilinear transform.
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.
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).
uint16_t foo
Definition main_demo5.c:58
static void notch_filter_update(struct SecondOrderNotchFilter *filter, int32_t *input_signal, int32_t *output_signal)
Notch filter propagate.
static void notch_filter_set_filter_frequency(struct SecondOrderNotchFilter *filter, float frequency)
Set notch filter frequency in Hz.
static void notch_filter_init(struct SecondOrderNotchFilter *filter, float cutoff_frequency, float bandwidth, uint16_t sample_frequency)
Initialize second order notch filter.
int16_t temp_pitch
#define MAX_PPRZ
Definition paparazzi.h:8
Paparazzi floating point algebra.
Paparazzi fixed point algebra.
Simple matrix helper macros.
#define MAT_MUL_VECT(_n, o, a, b)
o = a * b
int32_t pprz_itrig_cos(int32_t angle)
int32_t pprz_itrig_sin(int32_t angle)
uint16_t rpm_sensor_get_rpm(void)
Definition rpm_sensor.c:75
struct Int32Quat stab_sp_to_quat_i(struct StabilizationSetpoint *sp)
struct Int32Eulers stab_sp_to_eulers_i(struct StabilizationSetpoint *sp)
int32_t th_sp_to_thrust_i(struct ThrustSetpoint *th, int32_t thrust, uint8_t axis)
#define THRUST_AXIS_Z
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_PITCH
void indi_apply_measurement_notch_filters(int32_t _out[], int32_t _in[])
void stabilization_attitude_run(bool in_flight, struct StabilizationSetpoint *sp, struct ThrustSetpoint *thrust, int32_t *cmd)
Attitude control run function.
struct delayed_first_order_lowpass_filter_t actuator_model[INDI_DOF]
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_ROLL
#define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_P
void indi_apply_measurement_butterworth_filters(int32_t _out[], int32_t _in[])
void stabilization_attitude_heli_indi_set_steadystate_roll(float roll)
stabilization_attitude_heli_indi_set_steadystate_roll
void stabilization_attitude_enter(void)
Attitude control enter function.
struct SecondOrderNotchFilter actuator_notchfilter[INDI_DOF]
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_YAW
#define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_COMMAND_ROTATION
static void indi_apply_actuator_models(int32_t _out[], int32_t _in[])
void stabilization_attitude_heli_indi_set_steadystate_pitch(float pitch)
stabilization_attitude_heli_indi_set_steadystate_pitch
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_PITCH
static struct Int32Eulers stab_att_sp_euler
Butterworth2LowPass_int measurement_lowpass_filters[INDI_DOF]
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_THRUST
static struct Int32Quat sp_offset
#define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_PITCH
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...
static struct IndiController_int heli_indi_ctl
Butterworth2LowPass_int actuator_lowpass_filters[INDI_DOF]
void stabilization_attitude_heli_indi_set_steadystate_pitchroll()
stabilization_attitude_heli_indi_set_steadystate_pitchroll
#define STABILIZATION_ATTITUDE_HELI_INDI_PITCH_P
#define STABILIZATION_ATTITUDE_HELI_INDI_STEADY_STATE_ROLL
#define STABILIZATION_ATTITUDE_HELI_INDI_YAW_P
#define STABILIZATION_ATTITUDE_HELI_INDI_ROLL_COMMAND_ROTATION
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_THRUST
struct SecondOrderNotchFilter measurement_notchfilter[INDI_DOF]
void stabilization_attitude_heli_indi_init(void)
stabilization_attitude_heli_indi_init
struct HeliIndiGains heli_indi_gains
void indi_apply_actuator_butterworth_filters(int32_t _out[], int32_t _in[])
#define STABILIZATION_ATTITUDE_HELI_INDI_YAW_D
static struct Int32Quat stab_att_sp_quat
#define STABILIZATION_ATTITUDE_HELI_INDI_NOTCHFILT_BW_YAW
void indi_apply_actuator_notch_filters(int32_t _out[], int32_t _in[])
static void indi_apply_notch_filters(struct SecondOrderNotchFilter *filter, int32_t _out[], int32_t _in[])
#define STABILIZATION_ATTITUDE_HELI_INDI_BUTTERW_CUTOFF_ROLL
#define INDI_YAW_BUFFER_SIZE
Quaternion transformation functions.
API to get/set the generic vehicle states.
#define TRUE
Definition std.h:4
#define FALSE
Definition std.h:5
int32_t reference[INDI_DOF]
Range -MAX_PPRZ:MAX_PPRZ.
float sp_offset_pitch
Neutral pitch angle [deg].
int32_t command_out[2][INDI_DOF]
Command and command from previous measurement.
int32_t filtered_measurement[INDI_NR_FILTERS][INDI_DOF]
Filtered measurement.
int32_t measurement[INDI_DOF]
Raw measurement.
int32_t error[INDI_DOF]
virtual control minus measurement
float sp_offset_roll
Neutral roll angle [deg].
int32_t actuator_out[INDI_DOF]
Actuator position.
void(* apply_compensator_filters)(int32_t _out[], int32_t _in[])
void(* apply_actuator_filters[INDI_NR_FILTERS])(int32_t _out[], int32_t _in[])
int32_t du[INDI_DOF]
Actuator commanded increment.
int32_t pitch_comp_angle
Angle to rotate pitch/roll commands with INT32_ANGLE_FRAC.
int32_t roll_comp_angle
Angle to rotate pitch/roll commands with INT32_ANGLE_FRAC.
int32_t invG[INDI_DOF][INDI_DOF]
Inverse control effectiveness matrix.
bool enable_notch
Use notch filters.
void(* apply_actuator_models)(int32_t _out[], int32_t _in[])
int16_t motor_rpm
RPM of the main motor.
int32_t u_setpoint[INDI_DOF]
Actuator setpoint without compensator.
int32_t filtered_actuator[INDI_NR_FILTERS][INDI_DOF]
Filtered actuator position.
void(* apply_measurement_filters[INDI_NR_FILTERS])(int32_t _out[], int32_t _in[])
Stabilization setpoint.
Thrust setpoint // TODO to a setpoint header Structure to store the desired thrust vector with differ...
float alpha
Definition textons.c:133
int int32_t
Typedef defining 32 bit int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.