Paparazzi UAS  v5.12_stable-4-g9b43e9b
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
stabilization_indi.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) Ewoud Smeur <ewoud_smeur@msn.com>
3  * MAVLab Delft University of Technology
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 
37 
39 #include "state.h"
40 #include "generated/airframe.h"
42 #include "subsystems/actuators.h"
43 #include "subsystems/abi.h"
45 #include "wls/wls_alloc.h"
46 #include <stdio.h>
47 
48 //only 4 actuators supported for now
49 #define INDI_NUM_ACT 4
50 // outputs: roll, pitch, yaw, thrust
51 #define INDI_OUTPUTS 4
52 // Factor that the estimated G matrix is allowed to deviate from initial one
53 #define INDI_ALLOWED_G_FACTOR 2.0
54 // Scaling for the control effectiveness to make it readible
55 #define INDI_G_SCALING 1000.0
56 
62 int num_iter = 0;
63 
64 static void lms_estimation(void);
65 static void get_actuator_state(void);
66 static void calc_g1_element(float dx_error, int8_t i, int8_t j, float mu_extra);
67 static void calc_g2_element(float dx_error, int8_t j, float mu_extra);
68 static void calc_g1g2_pseudo_inv(void);
69 static void bound_g_mat(void);
70 
73  STABILIZATION_INDI_REF_ERR_P,
74  STABILIZATION_INDI_REF_ERR_Q,
75  STABILIZATION_INDI_REF_ERR_R,
76  STABILIZATION_INDI_REF_RATE_P,
77  STABILIZATION_INDI_REF_RATE_Q,
78  STABILIZATION_INDI_REF_RATE_R,
79 };
80 
81 #if STABILIZATION_INDI_USE_ADAPTIVE
82 bool indi_use_adaptive = true;
83 #else
84 bool indi_use_adaptive = false;
85 #endif
86 
87 #ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
88 float act_rate_limit[INDI_NUM_ACT] = STABILIZATION_INDI_ACT_RATE_LIMIT;
89 #endif
90 
91 #ifdef STABILIZATION_INDI_ACT_IS_SERVO
92 bool act_is_servo[INDI_NUM_ACT] = STABILIZATION_INDI_ACT_IS_SERVO;
93 #else
95 #endif
96 
97 #ifdef STABILIZATION_INDI_ACT_PREF
98 // Preferred (neutral, least energy) actuator value
99 float act_pref[INDI_NUM_ACT] = STABILIZATION_INDI_ACT_PREF;
100 #else
101 // Assume 0 is neutral
102 float act_pref[INDI_NUM_ACT] = {0.0};
103 #endif
104 
105 float act_dyn[INDI_NUM_ACT] = STABILIZATION_INDI_ACT_DYN;
106 
108 #ifndef STABILIZATION_INDI_MAX_RATE
109 #define STABILIZATION_INDI_MAX_RATE 6.0
110 #endif
111 
112 // variables needed for control
114 struct FloatRates angular_accel_ref = {0., 0., 0.};
115 float angular_acceleration[3] = {0., 0., 0.};
120 
121 // variables needed for estimation
130 
131 // The learning rate per axis (roll, pitch, yaw, thrust)
132 float mu1[INDI_OUTPUTS] = {0.00001, 0.00001, 0.000003, 0.000002};
133 // The learning rate for the propeller inertia (scaled by 512 wrt mu1)
134 float mu2 = 0.002;
135 
136 // other variables
138 
139 // Number of actuators used to provide thrust
141 
144 
146 static void rpm_cb(uint8_t sender_id, uint16_t *rpm, uint8_t num_act);
147 
149 static void thrust_cb(uint8_t sender_id, float thrust_increment);
152 
154 float g2[INDI_NUM_ACT] = STABILIZATION_INDI_G2; //scaled by INDI_G_SCALING
155 float g1[INDI_OUTPUTS][INDI_NUM_ACT] = {STABILIZATION_INDI_G1_ROLL,
156  STABILIZATION_INDI_G1_PITCH, STABILIZATION_INDI_G1_YAW, STABILIZATION_INDI_G1_THRUST
157  };
163 
169 
171 
172 void init_filters(void);
173 
174 #if PERIODIC_TELEMETRY
176 static void send_indi_g(struct transport_tx *trans, struct link_device *dev)
177 {
178  pprz_msg_send_INDI_G(trans, dev, AC_ID, INDI_NUM_ACT, g1_est[0],
179  INDI_NUM_ACT, g1_est[1],
180  INDI_NUM_ACT, g1_est[2],
181  INDI_NUM_ACT, g1_est[3],
183 }
184 
185 static void send_ahrs_ref_quat(struct transport_tx *trans, struct link_device *dev)
186 {
187  struct Int32Quat *quat = stateGetNedToBodyQuat_i();
188  pprz_msg_send_AHRS_REF_QUAT(trans, dev, AC_ID,
193  &(quat->qi),
194  &(quat->qx),
195  &(quat->qy),
196  &(quat->qz));
197 }
198 #endif
199 
204 {
205  // Initialize filters
206  init_filters();
207 
208  AbiBindMsgRPM(RPM_SENSOR_ID, &rpm_ev, rpm_cb);
209  AbiBindMsgTHRUST(THRUST_INCREMENT_ID, &thrust_ev, thrust_cb);
210 
216 
217  //Calculate G1G2_PSEUDO_INVERSE
219 
220  // Initialize the array of pointers to the rows of g1g2
221  uint8_t i;
222  for (i = 0; i < INDI_OUTPUTS; i++) {
223  Bwls[i] = g1g2[i];
224  }
225 
226  // Initialize the estimator matrices
227  float_vect_copy(g1_est[0], g1[0], INDI_OUTPUTS * INDI_NUM_ACT);
228  float_vect_copy(g2_est, g2, INDI_NUM_ACT);
229  // Remember the initial matrices
230  float_vect_copy(g1_init[0], g1[0], INDI_OUTPUTS * INDI_NUM_ACT);
231  float_vect_copy(g2_init, g2, INDI_NUM_ACT);
232 
233  // Assume all non-servos are delivering thrust
235  for (i = 0; i < INDI_NUM_ACT; i++) {
237  }
238 
239 #if PERIODIC_TELEMETRY
242 #endif
243 }
244 
254 {
255  /* reset psi setpoint to current psi angle */
257 
260 }
261 
265 void init_filters(void)
266 {
267  // tau = 1/(2*pi*Fc)
268  float tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF);
269  float tau_est = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF);
270  float sample_time = 1.0 / PERIODIC_FREQUENCY;
271  // Filtering of the gyroscope
272  int8_t i;
273  for (i = 0; i < 3; i++) {
274  init_butterworth_2_low_pass(&measurement_lowpass_filters[i], tau, sample_time, 0.0);
275  init_butterworth_2_low_pass(&estimation_output_lowpass_filters[i], tau_est, sample_time, 0.0);
276  }
277 
278  // Filtering of the actuators
279  for (i = 0; i < INDI_NUM_ACT; i++) {
280  init_butterworth_2_low_pass(&actuator_lowpass_filters[i], tau, sample_time, 0.0);
281  init_butterworth_2_low_pass(&estimation_input_lowpass_filters[i], tau_est, sample_time, 0.0);
282  }
283 
284  // Filtering of the accel body z
285  init_butterworth_2_low_pass(&acceleration_lowpass_filter, tau_est, sample_time, 0.0);
286 }
287 
292 {
293  /* set failsafe to zero roll/pitch and current heading */
296  stab_att_sp_quat.qx = 0;
297  stab_att_sp_quat.qy = 0;
299 }
300 
307 {
308  // stab_att_sp_euler.psi still used in ref..
309  stab_att_sp_euler = *rpy;
310 
312 }
313 
321 {
322  // stab_att_sp_euler.psi still used in ref..
324 
325  // compute sp_euler phi/theta for debugging/telemetry
326  /* Rotate horizontal commands to body frame by psi */
328  int32_t s_psi, c_psi;
329  PPRZ_ITRIG_SIN(s_psi, psi);
330  PPRZ_ITRIG_COS(c_psi, psi);
331  stab_att_sp_euler.phi = (-s_psi * cmd->x + c_psi * cmd->y) >> INT32_TRIG_FRAC;
332  stab_att_sp_euler.theta = -(c_psi * cmd->x + s_psi * cmd->y) >> INT32_TRIG_FRAC;
333 
334  quat_from_earth_cmd_i(&stab_att_sp_quat, cmd, heading);
335 }
336 
344 static void stabilization_indi_calc_cmd(struct Int32Quat *att_err, bool rate_control, bool in_flight)
345 {
346 
347  struct FloatRates rate_ref;
348  if (rate_control) { //Check if we are running the rate controller
351  rate_ref.r = (float)radio_control.values[RADIO_YAW] / MAX_PPRZ * STABILIZATION_INDI_MAX_RATE;
352  } else {
353  //calculate the virtual control (reference acceleration) based on a PD controller
354  rate_ref.p = reference_acceleration.err_p * QUAT1_FLOAT_OF_BFP(att_err->qx)
355  / reference_acceleration.rate_p;
356  rate_ref.q = reference_acceleration.err_q * QUAT1_FLOAT_OF_BFP(att_err->qy)
357  / reference_acceleration.rate_q;
358  rate_ref.r = reference_acceleration.err_r * QUAT1_FLOAT_OF_BFP(att_err->qz)
359  / reference_acceleration.rate_r;
360 
361  // Possibly we can use some bounding here
362  /*BoundAbs(rate_ref.r, 5.0);*/
363  }
364 
365  struct FloatRates *body_rates = stateGetBodyRates_f();
366 
367  //calculate the virtual control (reference acceleration) based on a PD controller
368  angular_accel_ref.p = (rate_ref.p - body_rates->p) * reference_acceleration.rate_p;
369  angular_accel_ref.q = (rate_ref.q - body_rates->q) * reference_acceleration.rate_q;
370  angular_accel_ref.r = (rate_ref.r - body_rates->r) * reference_acceleration.rate_r;
371 
372  g2_times_du = 0.0;
373  int8_t i;
374  for (i = 0; i < INDI_NUM_ACT; i++) {
375  g2_times_du += g2[i] * indi_du[i];
376  }
377  //G2 is scaled by INDI_G_SCALING to make it readable
379 
380  float v_thrust = 0.0;
381  if (indi_thrust_increment_set && in_flight) {
382  v_thrust = indi_thrust_increment;
383 
384  //update thrust command such that the current is correctly estimated
385  stabilization_cmd[COMMAND_THRUST] = 0;
386  for (i = 0; i < INDI_NUM_ACT; i++) {
387  stabilization_cmd[COMMAND_THRUST] += actuator_state[i] * -((int32_t) act_is_servo[i] - 1);
388  }
389  stabilization_cmd[COMMAND_THRUST] /= num_thrusters;
390 
391  } else {
392  // incremental thrust
393  for (i = 0; i < INDI_NUM_ACT; i++) {
394  v_thrust +=
395  (stabilization_cmd[COMMAND_THRUST] - actuator_state_filt_vect[i]) * Bwls[3][i];
396  }
397  }
398 
399  // Calculate the min and max increments
400  for (i = 0; i < INDI_NUM_ACT; i++) {
402  du_max[i] = MAX_PPRZ - actuator_state_filt_vect[i];
403  du_pref[i] = act_pref[i] - actuator_state_filt_vect[i];
404  }
405 
406  //State prioritization {W Roll, W pitch, W yaw, TOTAL THRUST}
407  static float Wv[INDI_OUTPUTS] = {1000, 1000, 1, 100};
408 
409  // The control objective in array format
410  indi_v[0] = (angular_accel_ref.p - angular_acceleration[0]);
411  indi_v[1] = (angular_accel_ref.q - angular_acceleration[1]);
412  indi_v[2] = (angular_accel_ref.r - angular_acceleration[2] + g2_times_du);
413  indi_v[3] = v_thrust;
414 
415 #if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
416  // Calculate the increment for each actuator
417  for (i = 0; i < INDI_NUM_ACT; i++) {
418  indi_du[i] = (g1g2_pseudo_inv[i][0] * indi_v[0])
419  + (g1g2_pseudo_inv[i][1] * indi_v[1])
420  + (g1g2_pseudo_inv[i][2] * indi_v[2])
421  + (g1g2_pseudo_inv[i][3] * indi_v[3]);
422  }
423 #else
424  // WLS Control Allocator
425  num_iter =
426  wls_alloc(indi_du, indi_v, du_min, du_max, Bwls, INDI_NUM_ACT, INDI_OUTPUTS, 0, 0, Wv, 0, du_min, 10000, 10);
427 #endif
428 
429  // Add the increments to the actuators
431 
432  // Bound the inputs to the actuators
433  for (i = 0; i < INDI_NUM_ACT; i++) {
434  if (act_is_servo[i]) {
435  BoundAbs(indi_u[i], MAX_PPRZ);
436  } else {
437  Bound(indi_u[i], 0, MAX_PPRZ);
438  }
439  }
440 
441  //Don't increment if not flying (not armed)
442  if (!in_flight) {
443  float_vect_zero(indi_u, INDI_NUM_ACT);
444  float_vect_zero(indi_du, INDI_NUM_ACT);
445  }
446 
447  // Propagate actuator filters
449  for (i = 0; i < INDI_NUM_ACT; i++) {
450  update_butterworth_2_low_pass(&actuator_lowpass_filters[i], actuator_state[i]);
451  update_butterworth_2_low_pass(&estimation_input_lowpass_filters[i], actuator_state[i]);
452  actuator_state_filt_vect[i] = actuator_lowpass_filters[i].o[0];
453 
454  // calculate derivatives for estimation
455  float actuator_state_filt_vectd_prev = actuator_state_filt_vectd[i];
456  actuator_state_filt_vectd[i] = (estimation_input_lowpass_filters[i].o[0] - estimation_input_lowpass_filters[i].o[1]) * PERIODIC_FREQUENCY;
457  actuator_state_filt_vectdd[i] = (actuator_state_filt_vectd[i] - actuator_state_filt_vectd_prev) * PERIODIC_FREQUENCY;
458  }
459 
460  // Use online effectiveness estimation only when flying
461  if (in_flight && indi_use_adaptive) {
462  lms_estimation();
463  }
464 
465  /*Commit the actuator command*/
466  for (i = 0; i < INDI_NUM_ACT; i++) {
467  actuators_pprz[i] = (int16_t) indi_u[i];
468  }
469 }
470 
477 void stabilization_indi_run(bool in_flight, bool rate_control)
478 {
479 
480  /* Propagate the filter on the gyroscopes */
481  struct FloatRates *body_rates = stateGetBodyRates_f();
482  float rate_vect[3] = {body_rates->p, body_rates->q, body_rates->r};
483  int8_t i;
484  for (i = 0; i < 3; i++) {
485  update_butterworth_2_low_pass(&measurement_lowpass_filters[i], rate_vect[i]);
486  update_butterworth_2_low_pass(&estimation_output_lowpass_filters[i], rate_vect[i]);
487 
488  //Calculate the angular acceleration via finite difference
489  angular_acceleration[i] = (measurement_lowpass_filters[i].o[0]
490  - measurement_lowpass_filters[i].o[1]) * PERIODIC_FREQUENCY;
491 
492  // Calculate derivatives for estimation
493  float estimation_rate_d_prev = estimation_rate_d[i];
494  estimation_rate_d[i] = (estimation_output_lowpass_filters[i].o[0] - estimation_output_lowpass_filters[i].o[1]) * PERIODIC_FREQUENCY;
495  estimation_rate_dd[i] = (estimation_rate_d[i] - estimation_rate_d_prev) * PERIODIC_FREQUENCY;
496  }
497 
498  /* attitude error */
499  struct Int32Quat att_err;
500  struct Int32Quat *att_quat = stateGetNedToBodyQuat_i();
501  int32_quat_inv_comp(&att_err, att_quat, &stab_att_sp_quat);
502  /* wrap it in the shortest direction */
503  int32_quat_wrap_shortest(&att_err);
504  int32_quat_normalize(&att_err);
505 
506  /* compute the INDI command */
507  stabilization_indi_calc_cmd(&att_err, rate_control, in_flight);
508 
509  // Set the stab_cmd to 42 to indicate that it is not used
510  stabilization_cmd[COMMAND_ROLL] = 42;
511  stabilization_cmd[COMMAND_PITCH] = 42;
512  stabilization_cmd[COMMAND_YAW] = 42;
513 
514  // Reset thrust increment boolean
516 }
517 
518 // This function reads rc commands
519 void stabilization_indi_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
520 {
521  struct FloatQuat q_sp;
522 #if USE_EARTH_BOUND_RC_SETPOINT
523  stabilization_attitude_read_rc_setpoint_quat_earth_bound_f(&q_sp, in_flight, in_carefree, coordinated_turn);
524 #else
525  stabilization_attitude_read_rc_setpoint_quat_f(&q_sp, in_flight, in_carefree, coordinated_turn);
526 #endif
527 
529 }
530 
538 {
539 #if INDI_RPM_FEEDBACK
541 #else
542  //actuator dynamics
543  int8_t i;
544  float UNUSED prev_actuator_state;
545  for (i = 0; i < INDI_NUM_ACT; i++) {
546  prev_actuator_state = actuator_state[i];
547 
549  + act_dyn[i] * (indi_u[i] - actuator_state[i]);
550 
551 #ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
552  if ((actuator_state[i] - prev_actuator_state) > act_rate_limit[i]) {
553  actuator_state[i] = prev_actuator_state + act_rate_limit[i];
554  } else if ((actuator_state[i] - prev_actuator_state) < -act_rate_limit[i]) {
555  actuator_state[i] = prev_actuator_state - act_rate_limit[i];
556  }
557 #endif
558  }
559 
560 #endif
561 }
562 
573 void calc_g1_element(float ddx_error, int8_t i, int8_t j, float mu)
574 {
575  g1_est[i][j] = g1_est[i][j] - du_estimation[j] * mu * ddx_error;
576 }
577 
587 void calc_g2_element(float ddx_error, int8_t j, float mu)
588 {
589  g2_est[j] = g2_est[j] - ddu_estimation[j] * mu * ddx_error;
590 }
591 
597 void lms_estimation(void)
598 {
599 
600  // Get the acceleration in body axes
601  struct Int32Vect3 *body_accel_i;
602  body_accel_i = stateGetAccelBody_i();
603  ACCELS_FLOAT_OF_BFP(body_accel_f, *body_accel_i);
604 
605  // Filter the acceleration in z axis
606  update_butterworth_2_low_pass(&acceleration_lowpass_filter, body_accel_f.z);
607 
608  // Calculate the derivative of the acceleration via finite difference
609  float indi_accel_d = (acceleration_lowpass_filter.o[0]
610  - acceleration_lowpass_filter.o[1]) * PERIODIC_FREQUENCY;
611 
612  // scale the inputs to avoid numerical errors
615 
616  float ddx_estimation[INDI_OUTPUTS] = {estimation_rate_dd[0], estimation_rate_dd[1], estimation_rate_dd[2], indi_accel_d};
617 
618  //Estimation of G
619  // TODO: only estimate when du_norm2 is large enough (enough input)
620  /*float du_norm2 = du_estimation[0]*du_estimation[0] + du_estimation[1]*du_estimation[1] +du_estimation[2]*du_estimation[2] + du_estimation[3]*du_estimation[3];*/
621  int8_t i;
622  for (i = 0; i < INDI_OUTPUTS; i++) {
623  // Calculate the error between prediction and measurement
624  float ddx_error = - ddx_estimation[i];
625  int8_t j;
626  for (j = 0; j < INDI_NUM_ACT; j++) {
627  ddx_error += g1_est[i][j] * du_estimation[j];
628  if (i == 2) {
629  // Changing the momentum of the rotors gives a counter torque
630  ddx_error += g2_est[j] * ddu_estimation[j];
631  }
632  }
633 
634  // when doing the yaw axis, also use G2
635  if (i == 2) {
636  for (j = 0; j < INDI_NUM_ACT; j++) {
637  calc_g2_element(ddx_error, j, mu2);
638  }
639  } else if (i == 3) {
640  // If the acceleration change is very large (rough landing), don't adapt
641  if (fabs(indi_accel_d) > 60.0) {
642  ddx_error = 0.0;
643  }
644  }
645 
646  // Calculate the row of the G1 matrix corresponding to this axis
647  for (j = 0; j < INDI_NUM_ACT; j++) {
648  calc_g1_element(ddx_error, i, j, mu1[i]);
649  }
650  }
651 
652  bound_g_mat();
653 
654  // Save the calculated matrix to G1 and G2
655  // until thrust is included, first part of the array
656  float_vect_copy(g1[0], g1_est[0], INDI_OUTPUTS * INDI_NUM_ACT);
657  float_vect_copy(g2, g2_est, INDI_NUM_ACT);
658 
659  // Calculate the inverse of (G1+G2)
661 }
662 
667 {
668 
669  //sum of G1 and G2
670  int8_t i;
671  int8_t j;
672  for (i = 0; i < INDI_OUTPUTS; i++) {
673  for (j = 0; j < INDI_NUM_ACT; j++) {
674  if (i != 2) {
675  g1g2[i][j] = g1[i][j] / INDI_G_SCALING;
676  } else {
677  g1g2[i][j] = (g1[i][j] + g2[j]) / INDI_G_SCALING;
678  }
679  }
680  }
681 
682  //G1G2*transpose(G1G2)
683  //calculate matrix multiplication of its transpose INDI_OUTPUTSxnum_act x num_actxINDI_OUTPUTS
684  float element = 0;
685  int8_t row;
686  int8_t col;
687  for (row = 0; row < INDI_OUTPUTS; row++) {
688  for (col = 0; col < INDI_OUTPUTS; col++) {
689  element = 0;
690  for (i = 0; i < INDI_NUM_ACT; i++) {
691  element = element + g1g2[row][i] * g1g2[col][i];
692  }
693  g1g2_trans_mult[row][col] = element;
694  }
695  }
696 
697  //there are numerical errors if the scaling is not right.
698  float_vect_scale(g1g2_trans_mult[0], 100.0, INDI_OUTPUTS * INDI_OUTPUTS);
699 
700  //inverse of 4x4 matrix
702 
703  //scale back
704  float_vect_scale(g1g2inv[0], 100.0, INDI_OUTPUTS * INDI_OUTPUTS);
705 
706  //G1G2'*G1G2inv
707  //calculate matrix multiplication INDI_NUM_ACTxINDI_OUTPUTS x INDI_OUTPUTSxINDI_OUTPUTS
708  for (row = 0; row < INDI_NUM_ACT; row++) {
709  for (col = 0; col < INDI_OUTPUTS; col++) {
710  element = 0;
711  for (i = 0; i < INDI_OUTPUTS; i++) {
712  element = element + g1g2[i][row] * g1g2inv[col][i];
713  }
714  g1g2_pseudo_inv[row][col] = element;
715  }
716  }
717 }
718 
719 static void rpm_cb(uint8_t __attribute__((unused)) sender_id, uint16_t UNUSED *rpm, uint8_t UNUSED num_act)
720 {
721 #if INDI_RPM_FEEDBACK
722  int8_t i;
723  for (i = 0; i < num_act; i++) {
724  act_obs[i] = (rpm[i] - get_servo_min(i));
725  act_obs[i] *= (MAX_PPRZ / (float)(get_servo_max(i) - get_servo_min(i)));
726  Bound(act_obs[i], 0, MAX_PPRZ);
727  }
728 #endif
729 }
730 
734 static void thrust_cb(uint8_t UNUSED sender_id, float thrust_increment)
735 {
736  indi_thrust_increment = thrust_increment;
738 }
739 
740 static void bound_g_mat(void)
741 {
742  int8_t i;
743  int8_t j;
744  for (j = 0; j < INDI_NUM_ACT; j++) {
745  float max_limit;
746  float min_limit;
747 
748  // Limit the values of the estimated G1 matrix
749  for (i = 0; i < INDI_OUTPUTS; i++) {
750  if (g1_init[i][j] > 0.0) {
751  max_limit = g1_init[i][j] * INDI_ALLOWED_G_FACTOR;
752  min_limit = g1_init[i][j] / INDI_ALLOWED_G_FACTOR;
753  } else {
754  max_limit = g1_init[i][j] / INDI_ALLOWED_G_FACTOR;
755  min_limit = g1_init[i][j] * INDI_ALLOWED_G_FACTOR;
756  }
757 
758  if (g1_est[i][j] > max_limit) {
759  g1_est[i][j] = max_limit;
760  }
761  if (g1_est[i][j] < min_limit) {
762  g1_est[i][j] = min_limit;
763  }
764  }
765 
766  // Do the same for the G2 matrix
767  if (g2_init[j] > 0.0) {
768  max_limit = g2_init[j] * INDI_ALLOWED_G_FACTOR;
769  min_limit = g2_init[j] / INDI_ALLOWED_G_FACTOR;
770  } else {
771  max_limit = g2_init[j] / INDI_ALLOWED_G_FACTOR;
772  min_limit = g2_init[j] * INDI_ALLOWED_G_FACTOR;
773  }
774 
775  if (g2_est[j] > max_limit) {
776  g2_est[j] = max_limit;
777  }
778  if (g2_est[j] < min_limit) {
779  g2_est[j] = min_limit;
780  }
781  }
782 }
int32_t psi
in rad with INT32_ANGLE_FRAC
Event structure to store callbacks in a linked list.
Definition: abi_common.h:65
unsigned short uint16_t
Definition: types.h:16
float g1g2[INDI_OUTPUTS][INDI_NUM_ACT]
static float update_butterworth_2_low_pass(Butterworth2LowPass *filter, float value)
Update second order Butterworth low pass filter state with a new value.
static void float_vect_sum(float *o, const float *a, const float *b, const int n)
o = a + b
void stabilization_indi_init(void)
Function that initializes important values upon engaging INDI.
float du_pref[INDI_NUM_ACT]
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 init_butterworth_2_low_pass(Butterworth2LowPass *filter, float tau, float sample_time, float value)
Init a second order Butterworth filter.
static struct Int32Vect3 * stateGetAccelBody_i(void)
Get acceleration in Body coordinates (int).
Definition: state.h:953
static void int32_quat_normalize(struct Int32Quat *q)
normalize a quaternion inplace
void stabilization_indi_set_failsafe_setpoint(void)
Function that calculates the failsafe setpoint.
struct ReferenceSystem reference_acceleration
bool indi_thrust_increment_set
void int32_quat_inv_comp(struct Int32Quat *b2c, struct Int32Quat *a2b, struct Int32Quat *a2c)
Composition (multiplication) of two quaternions.
void init_filters(void)
Function that resets the filters to zeros.
#define RADIO_ROLL
Definition: spektrum_arch.h:43
Quaternion transformation functions.
float du_min[INDI_NUM_ACT]
#define RADIO_YAW
Definition: spektrum_arch.h:45
Periodic telemetry system header (includes downlink utility and generated code).
General attitude stabilization interface for rotorcrafts.
float * Bwls[INDI_OUTPUTS]
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)
float r
in rad/s
Butterworth2LowPass actuator_lowpass_filters[INDI_NUM_ACT]
#define STABILIZATION_INDI_MAX_RATE
Maximum rate you can request in RC rate mode (rad/s)
Read an attitude setpoint from the RC.
Main include for ABI (AirBorneInterface).
static void calc_g2_element(float dx_error, int8_t j, float mu_extra)
void stabilization_indi_set_rpy_setpoint_i(struct Int32Eulers *rpy)
Butterworth2LowPass acceleration_lowpass_filter
#define RPM_SENSOR_ID
void stabilization_indi_enter(void)
Function that resets important values upon engaging INDI.
void float_mat_inv_4d(float invOut[16], float mat_in[16])
4x4 Matrix inverse
float q
in rad/s
float p
in rad/s
pprz_t values[RADIO_CONTROL_NB_CHANNEL]
Definition: radio_control.h:58
static void stabilization_indi_calc_cmd(struct Int32Quat *att_err, bool rate_control, bool in_flight)
struct FloatVect3 body_accel_f
static struct Int32Quat * stateGetNedToBodyQuat_i(void)
Get vehicle body attitude quaternion (int).
Definition: state.h:1113
float indi_v[INDI_OUTPUTS]
int num_iter
static void calc_g1_element(float dx_error, int8_t i, int8_t j, float mu_extra)
void stabilization_indi_run(bool in_flight, bool rate_control)
Butterworth2LowPass estimation_input_lowpass_filters[INDI_NUM_ACT]
float estimation_rate_dd[INDI_NUM_ACT]
float o[2]
output history
Roation quaternion.
float g2_est[INDI_NUM_ACT]
void stabilization_attitude_read_rc_setpoint_quat_earth_bound_f(struct FloatQuat *q_sp, bool in_flight, bool in_carefree, bool coordinated_turn)
abi_event thrust_ev
float g1_est[INDI_OUTPUTS][INDI_NUM_ACT]
#define PPRZ_ITRIG_SIN(_s, _a)
#define INDI_ALLOWED_G_FACTOR
Hardware independent API for actuators (servos, motor controllers).
float mu2
float act_dyn[INDI_NUM_ACT]
static float heading
Definition: ahrs_infrared.c:45
Paparazzi floating point algebra.
float g1g2_trans_mult[INDI_OUTPUTS][INDI_OUTPUTS]
float du_max[INDI_NUM_ACT]
float ddu_estimation[INDI_NUM_ACT]
uint16_t rpm
Definition: rpm_sensor.c:33
static void bound_g_mat(void)
#define RADIO_PITCH
Definition: spektrum_arch.h:44
euler angles
void stabilization_indi_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
#define INDI_NUM_ACT
static void float_vect_zero(float *a, const int n)
a = 0
float act_pref[INDI_NUM_ACT]
#define QUAT_BFP_OF_REAL(_qi, _qf)
Definition: pprz_algebra.h:696
signed short int16_t
Definition: types.h:17
int32_t stabilization_att_indi_cmd[COMMANDS_NB]
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
#define STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF
float g1g2_pseudo_inv[INDI_NUM_ACT][INDI_OUTPUTS]
struct RadioControl radio_control
Definition: radio_control.c:30
float estimation_rate_d[INDI_NUM_ACT]
#define INDI_G_SCALING
static void float_vect_smul(float *o, const float *a, const float s, const int n)
o = a * s
void quat_from_earth_cmd_i(struct Int32Quat *quat, struct Int32Vect2 *cmd, int32_t heading)
static void calc_g1g2_pseudo_inv(void)
Function that calculates the pseudo-inverse of (G1+G2).
struct FloatRates angular_accel_ref
#define ACCELS_FLOAT_OF_BFP(_ef, _ei)
Definition: pprz_algebra.h:739
static void thrust_cb(uint8_t sender_id, float thrust_increment)
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
Definition: state.h:1200
#define THRUST_INCREMENT_ID
signed long int32_t
Definition: types.h:19
int32_t num_thrusters
static void lms_estimation(void)
Function that estimates the control effectiveness of each actuator online.
static void get_actuator_state(void)
Function that tries to get actuator feedback.
#define QUAT1_FLOAT_OF_BFP(_qi)
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:73
#define INT32_TRIG_FRAC
void stabilization_indi_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t heading)
float actuator_state[INDI_NUM_ACT]
bool indi_use_adaptive
#define STABILIZATION_INDI_FILT_CUTOFF
float g2_times_du
static void send_indi_g(struct transport_tx *trans, struct link_device *dev)
float du_estimation[INDI_NUM_ACT]
Butterworth2LowPass estimation_output_lowpass_filters[3]
int32_t phi
in rad with INT32_ANGLE_FRAC
unsigned char uint8_t
Definition: types.h:14
int wls_alloc(float *u, float *v, float *umin, float *umax, float **B, int n_u, int n_v, float *u_guess, float *W_init, float *Wv, float *Wu, float *up, float gamma_sq, int imax)
active set algorithm for control allocation
Definition: wls_alloc.c:101
float actuator_state_filt_vectd[INDI_NUM_ACT]
API to get/set the generic vehicle states.
#define INDI_OUTPUTS
bool act_is_servo[INDI_NUM_ACT]
float indi_du[INDI_NUM_ACT]
static void float_vect_scale(float *a, const float s, const int n)
a *= s
static void int32_quat_wrap_shortest(struct Int32Quat *q)
static void float_vect_copy(float *a, const float *b, const int n)
a = b
float act_obs[INDI_NUM_ACT]
int32_t stabilization_cmd[COMMANDS_NB]
Stabilization commands.
Definition: stabilization.c:28
static void send_ahrs_ref_quat(struct transport_tx *trans, struct link_device *dev)
float mu1[INDI_OUTPUTS]
float g2_init[INDI_NUM_ACT]
float g2[INDI_NUM_ACT]
float angular_acceleration[3]
Butterworth2LowPass measurement_lowpass_filters[3]
float indi_u[INDI_NUM_ACT]
Second order low pass filter structure.
#define MAX_PPRZ
Definition: paparazzi.h:8
abi_event rpm_ev
signed char int8_t
Definition: types.h:15
static struct Int32Eulers * stateGetNedToBodyEulers_i(void)
Get vehicle body attitude euler angles (int).
Definition: state.h:1125
float actuator_state_filt_vect[INDI_NUM_ACT]
float g1_init[INDI_OUTPUTS][INDI_NUM_ACT]
static void rpm_cb(uint8_t sender_id, uint16_t *rpm, uint8_t num_act)
float g1[INDI_OUTPUTS][INDI_NUM_ACT]
Rotation quaternion.
angular rates
float g1g2inv[INDI_OUTPUTS][INDI_OUTPUTS]
float actuator_state_filt_vectdd[INDI_NUM_ACT]
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:46
float indi_thrust_increment
struct Int32Quat stab_att_sp_quat
with INT32_QUAT_FRAC
struct Int32Eulers stab_att_sp_euler
with INT32_ANGLE_FRAC
#define PPRZ_ITRIG_COS(_c, _a)