/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.c

https://github.com/AshuLara/paparazzi_lisa · C · 148 lines · 87 code · 24 blank · 37 comment · 1 complexity · 618baf2e122017fc2cf49d5350de480e MD5 · raw file

  1. /*
  2. * $Id$
  3. *
  4. * Copyright (C) 2008-2009 Antoine Drouin <poinix@gmail.com>
  5. *
  6. * This file is part of paparazzi.
  7. *
  8. * paparazzi is free software; you can redistribute it and/or modify
  9. * it under the terms of the GNU General Public License as published by
  10. * the Free Software Foundation; either version 2, or (at your option)
  11. * any later version.
  12. *
  13. * paparazzi is distributed in the hope that it will be useful,
  14. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  15. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  16. * GNU General Public License for more details.
  17. *
  18. * You should have received a copy of the GNU General Public License
  19. * along with paparazzi; see the file COPYING. If not, write to
  20. * the Free Software Foundation, 59 Temple Place - Suite 330,
  21. * Boston, MA 02111-1307, USA.
  22. */
  23. /** \file stabilization_attitude_ref_float.c
  24. * \brief Booz attitude reference generation (quaternion float version)
  25. *
  26. */
  27. #include "generated/airframe.h"
  28. #include "firmwares/rotorcraft/stabilization.h"
  29. #include "subsystems/ahrs.h"
  30. #include "stabilization_attitude_ref_float.h"
  31. #include "quat_setpoint.h"
  32. #define REF_ACCEL_MAX_P STABILIZATION_ATTITUDE_FLOAT_REF_MAX_PDOT
  33. #define REF_ACCEL_MAX_Q STABILIZATION_ATTITUDE_FLOAT_REF_MAX_QDOT
  34. #define REF_ACCEL_MAX_R STABILIZATION_ATTITUDE_FLOAT_REF_MAX_RDOT
  35. struct FloatEulers stab_att_sp_euler;
  36. struct FloatQuat stab_att_sp_quat;
  37. struct FloatEulers stab_att_ref_euler;
  38. struct FloatQuat stab_att_ref_quat;
  39. struct FloatRates stab_att_ref_rate;
  40. struct FloatRates stab_att_ref_accel;
  41. struct FloatRefModel stab_att_ref_model[STABILIZATION_ATTITUDE_FLOAT_GAIN_NB];
  42. static int ref_idx = STABILIZATION_ATTITUDE_FLOAT_GAIN_IDX_DEFAULT;
  43. static const float omega_p[] = STABILIZATION_ATTITUDE_FLOAT_REF_OMEGA_P;
  44. static const float zeta_p[] = STABILIZATION_ATTITUDE_FLOAT_REF_ZETA_P;
  45. static const float omega_q[] = STABILIZATION_ATTITUDE_FLOAT_REF_OMEGA_Q;
  46. static const float zeta_q[] = STABILIZATION_ATTITUDE_FLOAT_REF_ZETA_Q;
  47. static const float omega_r[] = STABILIZATION_ATTITUDE_FLOAT_REF_OMEGA_R;
  48. static const float zeta_r[] = STABILIZATION_ATTITUDE_FLOAT_REF_ZETA_R;
  49. static void reset_psi_ref_from_body(void) {
  50. stab_att_ref_euler.psi = ahrs_float.ltp_to_body_euler.psi;
  51. stab_att_ref_rate.r = 0;
  52. stab_att_ref_accel.r = 0;
  53. }
  54. static void update_ref_quat_from_eulers(void) {
  55. struct FloatRMat ref_rmat;
  56. #ifdef STICKS_RMAT312
  57. FLOAT_RMAT_OF_EULERS_312(ref_rmat, stab_att_ref_euler);
  58. #else
  59. FLOAT_RMAT_OF_EULERS_321(ref_rmat, stab_att_ref_euler);
  60. #endif
  61. FLOAT_QUAT_OF_RMAT(stab_att_ref_quat, ref_rmat);
  62. FLOAT_QUAT_WRAP_SHORTEST(stab_att_ref_quat);
  63. }
  64. void stabilization_attitude_ref_init(void) {
  65. FLOAT_EULERS_ZERO(stab_att_sp_euler);
  66. FLOAT_QUAT_ZERO( stab_att_sp_quat);
  67. FLOAT_EULERS_ZERO(stab_att_ref_euler);
  68. FLOAT_QUAT_ZERO( stab_att_ref_quat);
  69. FLOAT_RATES_ZERO( stab_att_ref_rate);
  70. FLOAT_RATES_ZERO( stab_att_ref_accel);
  71. for (int i = 0; i < STABILIZATION_ATTITUDE_FLOAT_GAIN_NB; i++) {
  72. RATES_ASSIGN(stab_att_ref_model[i].omega, omega_p[i], omega_q[i], omega_r[i]);
  73. RATES_ASSIGN(stab_att_ref_model[i].zeta, zeta_p[i], zeta_q[i], zeta_r[i]);
  74. }
  75. }
  76. void stabilization_attitude_ref_schedule(uint8_t idx)
  77. {
  78. ref_idx = idx;
  79. }
  80. void stabilization_attitude_ref_enter()
  81. {
  82. reset_psi_ref_from_body();
  83. stabilization_attitude_sp_enter();
  84. update_ref_quat_from_eulers();
  85. }
  86. /*
  87. * Reference
  88. */
  89. #ifdef BOOZ_AP_PERIODIC_PRESCALE
  90. #define DT_UPDATE ((float) BOOZ_AP_PERIODIC_PRESCALE / (float) PERIODIC_FREQ)
  91. #else
  92. #define DT_UPDATE (1./512.)
  93. #endif
  94. void stabilization_attitude_ref_update() {
  95. /* integrate reference attitude */
  96. struct FloatQuat qdot;
  97. FLOAT_QUAT_DERIVATIVE(qdot, stab_att_ref_rate, stab_att_ref_quat);
  98. QUAT_SMUL(qdot, qdot, DT_UPDATE);
  99. QUAT_ADD(stab_att_ref_quat, qdot);
  100. FLOAT_QUAT_NORMALIZE(stab_att_ref_quat);
  101. /* integrate reference rotational speeds */
  102. struct FloatRates delta_rate;
  103. RATES_SMUL(delta_rate, stab_att_ref_accel, DT_UPDATE);
  104. RATES_ADD(stab_att_ref_rate, delta_rate);
  105. /* compute reference angular accelerations */
  106. struct FloatQuat err;
  107. /* compute reference attitude error */
  108. FLOAT_QUAT_INV_COMP(err, stab_att_sp_quat, stab_att_ref_quat);
  109. /* wrap it in the shortest direction */
  110. FLOAT_QUAT_WRAP_SHORTEST(err);
  111. /* propagate the 2nd order linear model */
  112. stab_att_ref_accel.p = -2.*stab_att_ref_model[ref_idx].zeta.p*stab_att_ref_model[ref_idx].omega.p*stab_att_ref_rate.p
  113. - stab_att_ref_model[ref_idx].omega.p*stab_att_ref_model[ref_idx].omega.p*err.qx;
  114. stab_att_ref_accel.q = -2.*stab_att_ref_model[ref_idx].zeta.q*stab_att_ref_model[ref_idx].omega.q*stab_att_ref_rate.q
  115. - stab_att_ref_model[ref_idx].omega.q*stab_att_ref_model[ref_idx].omega.q*err.qy;
  116. stab_att_ref_accel.r = -2.*stab_att_ref_model[ref_idx].zeta.r*stab_att_ref_model[ref_idx].omega.r*stab_att_ref_rate.r
  117. - stab_att_ref_model[ref_idx].omega.r*stab_att_ref_model[ref_idx].omega.r*err.qz;
  118. /* saturate acceleration */
  119. const struct FloatRates MIN_ACCEL = { -REF_ACCEL_MAX_P, -REF_ACCEL_MAX_Q, -REF_ACCEL_MAX_R };
  120. const struct FloatRates MAX_ACCEL = { REF_ACCEL_MAX_P, REF_ACCEL_MAX_Q, REF_ACCEL_MAX_R };
  121. RATES_BOUND_BOX(stab_att_ref_accel, MIN_ACCEL, MAX_ACCEL);
  122. /* compute ref_euler */
  123. FLOAT_EULERS_OF_QUAT(stab_att_ref_euler, stab_att_ref_quat);
  124. }