Airspeed_Calibration.cpp 5.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184
  1. /*
  2. * auto_calibration.cpp - airspeed auto calibration
  3. *
  4. * Algorithm by Paul Riseborough
  5. *
  6. */
  7. #include <AP_Common/AP_Common.h>
  8. #include <AP_HAL/AP_HAL.h>
  9. #include <AP_Math/AP_Math.h>
  10. #include <GCS_MAVLink/GCS.h>
  11. #include <AP_Baro/AP_Baro.h>
  12. #include "AP_Airspeed.h"
  13. extern const AP_HAL::HAL& hal;
  14. // constructor - fill in all the initial values
  15. Airspeed_Calibration::Airspeed_Calibration()
  16. : P(100, 0, 0,
  17. 0, 100, 0,
  18. 0, 0, 0.000001f)
  19. , Q0(0.01f)
  20. , Q1(0.0000005f)
  21. , state(0, 0, 0)
  22. , DT(1)
  23. {
  24. }
  25. /*
  26. initialise the ratio
  27. */
  28. void Airspeed_Calibration::init(float initial_ratio)
  29. {
  30. state.z = 1.0f / sqrtf(initial_ratio);
  31. }
  32. /*
  33. update the state of the airspeed calibration - needs to be called
  34. once a second
  35. */
  36. float Airspeed_Calibration::update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
  37. {
  38. // Perform the covariance prediction
  39. // Q is a diagonal matrix so only need to add three terms in
  40. // C code implementation
  41. // P = P + Q;
  42. P.a.x += Q0;
  43. P.b.y += Q0;
  44. P.c.z += Q1;
  45. // Perform the predicted measurement using the current state estimates
  46. // No state prediction required because states are assumed to be time
  47. // invariant plus process noise
  48. // Ignore vertical wind component
  49. float TAS_pred = state.z * norm(vg.x - state.x, vg.y - state.y, vg.z);
  50. float TAS_mea = airspeed;
  51. // Calculate the observation Jacobian H_TAS
  52. float SH1 = sq(vg.y - state.y) + sq(vg.x - state.x);
  53. if (SH1 < 0.000001f) {
  54. // avoid division by a small number
  55. return state.z;
  56. }
  57. float SH2 = 1/sqrtf(SH1);
  58. // observation Jacobian
  59. Vector3f H_TAS(
  60. -(state.z*SH2*(2*vg.x - 2*state.x))/2,
  61. -(state.z*SH2*(2*vg.y - 2*state.y))/2,
  62. 1/SH2);
  63. // Calculate the fusion innovation covariance assuming a TAS measurement
  64. // noise of 1.0 m/s
  65. // S = H_TAS*P*H_TAS' + 1.0; % [1 x 3] * [3 x 3] * [3 x 1] + [1 x 1]
  66. Vector3f PH = P * H_TAS;
  67. float S = H_TAS * PH + 1.0f;
  68. // Calculate the Kalman gain
  69. // [3 x 3] * [3 x 1] / [1 x 1]
  70. Vector3f KG = PH / S;
  71. // Update the states
  72. state += KG*(TAS_mea - TAS_pred); // [3 x 1] + [3 x 1] * [1 x 1]
  73. // Update the covariance matrix
  74. Vector3f HP2 = H_TAS * P;
  75. P -= KG.mul_rowcol(HP2);
  76. // force symmetry on the covariance matrix - necessary due to rounding
  77. // errors
  78. float P12 = 0.5f * (P.a.y + P.b.x);
  79. float P13 = 0.5f * (P.a.z + P.c.x);
  80. float P23 = 0.5f * (P.b.z + P.c.y);
  81. P.a.y = P.b.x = P12;
  82. P.a.z = P.c.x = P13;
  83. P.b.z = P.c.y = P23;
  84. // Constrain diagonals to be non-negative - protects against rounding errors
  85. P.a.x = MAX(P.a.x, 0.0f);
  86. P.b.y = MAX(P.b.y, 0.0f);
  87. P.c.z = MAX(P.c.z, 0.0f);
  88. state.x = constrain_float(state.x, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
  89. state.y = constrain_float(state.y, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
  90. state.z = constrain_float(state.z, 0.5f, 1.0f);
  91. return state.z;
  92. }
  93. /*
  94. called once a second to do calibration update
  95. */
  96. void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
  97. {
  98. if (!param[i].autocal) {
  99. // auto-calibration not enabled
  100. return;
  101. }
  102. // set state.z based on current ratio, this allows the operator to
  103. // override the current ratio in flight with autocal, which is
  104. // very useful both for testing and to force a reasonable value.
  105. float ratio = constrain_float(param[i].ratio, 1.0f, 4.0f);
  106. state[i].calibration.state.z = 1.0f / sqrtf(ratio);
  107. // calculate true airspeed, assuming a airspeed ratio of 1.0
  108. float dpress = MAX(get_differential_pressure(), 0);
  109. float true_airspeed = sqrtf(dpress) * AP::baro().get_EAS2TAS();
  110. float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
  111. if (isnan(zratio) || isinf(zratio)) {
  112. return;
  113. }
  114. // this constrains the resulting ratio to between 1.0 and 4.0
  115. zratio = constrain_float(zratio, 0.5f, 1.0f);
  116. param[i].ratio.set(1/sq(zratio));
  117. if (state[i].counter > 60) {
  118. if (state[i].last_saved_ratio > 1.05f*param[i].ratio ||
  119. state[i].last_saved_ratio < 0.95f*param[i].ratio) {
  120. param[i].ratio.save();
  121. state[i].last_saved_ratio = param[i].ratio;
  122. state[i].counter = 0;
  123. }
  124. } else {
  125. state[i].counter++;
  126. }
  127. }
  128. /*
  129. called once a second to do calibration update
  130. */
  131. void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
  132. {
  133. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  134. update_calibration(i, vground, max_airspeed_allowed_during_cal);
  135. }
  136. send_airspeed_calibration(vground);
  137. }
  138. void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground)
  139. {
  140. const mavlink_airspeed_autocal_t packet{
  141. vx: vground.x,
  142. vy: vground.y,
  143. vz: vground.z,
  144. diff_pressure: get_differential_pressure(primary),
  145. EAS2TAS: AP::baro().get_EAS2TAS(),
  146. ratio: param[primary].ratio.get(),
  147. state_x: state[primary].calibration.state.x,
  148. state_y: state[primary].calibration.state.y,
  149. state_z: state[primary].calibration.state.z,
  150. Pax: state[primary].calibration.P.a.x,
  151. Pby: state[primary].calibration.P.b.y,
  152. Pcz: state[primary].calibration.P.c.z
  153. };
  154. gcs().send_to_active_channels(MAVLINK_MSG_ID_AIRSPEED_AUTOCAL,
  155. (const char *)&packet);
  156. }