AP_AHRS_View.h 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204
  1. #pragma once
  2. /*
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. /*
  15. * AHRS View class - for creating a 2nd view of the vehicle attitude
  16. *
  17. */
  18. #include "AP_AHRS.h"
  19. class AP_AHRS_View
  20. {
  21. public:
  22. // Constructor
  23. AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation, float pitch_trim_deg=0);
  24. // update state
  25. void update(bool skip_ins_update=false);
  26. // empty virtual destructor
  27. virtual ~AP_AHRS_View() {}
  28. // return a smoothed and corrected gyro vector
  29. const Vector3f &get_gyro(void) const {
  30. return gyro;
  31. }
  32. // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
  33. Vector3f get_gyro_latest(void) const;
  34. // return a DCM rotation matrix representing our current attitude in this view
  35. const Matrix3f &get_rotation_body_to_ned(void) const {
  36. return rot_body_to_ned;
  37. }
  38. // return a Quaternion representing our current attitude in this view
  39. void get_quat_body_to_ned(Quaternion &quat) const {
  40. quat.from_rotation_matrix(rot_body_to_ned);
  41. }
  42. // apply pitch trim
  43. void set_pitch_trim(float trim_deg);
  44. // helper trig value accessors
  45. float cos_roll() const {
  46. return trig.cos_roll;
  47. }
  48. float cos_pitch() const {
  49. return trig.cos_pitch;
  50. }
  51. float cos_yaw() const {
  52. return trig.cos_yaw;
  53. }
  54. float sin_roll() const {
  55. return trig.sin_roll;
  56. }
  57. float sin_pitch() const {
  58. return trig.sin_pitch;
  59. }
  60. float sin_yaw() const {
  61. return trig.sin_yaw;
  62. }
  63. /*
  64. wrappers around ahrs functions which pass-thru directly. See
  65. AP_AHRS.h for description of each function
  66. */
  67. bool get_position(struct Location &loc) const WARN_IF_UNUSED {
  68. return ahrs.get_position(loc);
  69. }
  70. Vector3f wind_estimate(void) {
  71. return ahrs.wind_estimate();
  72. }
  73. bool airspeed_estimate(float *airspeed_ret) const WARN_IF_UNUSED {
  74. return ahrs.airspeed_estimate(airspeed_ret);
  75. }
  76. bool airspeed_estimate_true(float *airspeed_ret) const WARN_IF_UNUSED {
  77. return ahrs.airspeed_estimate_true(airspeed_ret);
  78. }
  79. float get_EAS2TAS(void) const {
  80. return ahrs.get_EAS2TAS();
  81. }
  82. Vector2f groundspeed_vector(void) {
  83. return ahrs.groundspeed_vector();
  84. }
  85. bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED {
  86. return ahrs.get_velocity_NED(vec);
  87. }
  88. bool get_expected_mag_field_NED(Vector3f &ret) const WARN_IF_UNUSED {
  89. return ahrs.get_expected_mag_field_NED(ret);
  90. }
  91. bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED {
  92. return ahrs.get_relative_position_NED_home(vec);
  93. }
  94. bool get_relative_position_NED_origin(Vector3f &vec) const WARN_IF_UNUSED {
  95. return ahrs.get_relative_position_NED_origin(vec);
  96. }
  97. bool get_relative_position_NE_home(Vector2f &vecNE) const WARN_IF_UNUSED {
  98. return ahrs.get_relative_position_NE_home(vecNE);
  99. }
  100. bool get_relative_position_NE_origin(Vector2f &vecNE) const WARN_IF_UNUSED {
  101. return ahrs.get_relative_position_NE_origin(vecNE);
  102. }
  103. void get_relative_position_D_home(float &posD) const {
  104. ahrs.get_relative_position_D_home(posD);
  105. }
  106. bool get_relative_position_D_origin(float &posD) const WARN_IF_UNUSED {
  107. return ahrs.get_relative_position_D_origin(posD);
  108. }
  109. float groundspeed(void) {
  110. return ahrs.groundspeed();
  111. }
  112. const Vector3f &get_accel_ef_blended(void) const {
  113. return ahrs.get_accel_ef_blended();
  114. }
  115. uint32_t getLastPosNorthEastReset(Vector2f &pos) const WARN_IF_UNUSED {
  116. return ahrs.getLastPosNorthEastReset(pos);
  117. }
  118. uint32_t getLastPosDownReset(float &posDelta) const WARN_IF_UNUSED {
  119. return ahrs.getLastPosDownReset(posDelta);
  120. }
  121. // rotate a 2D vector from earth frame to body frame
  122. // in result, x is forward, y is right
  123. Vector2f rotate_earth_to_body2D(const Vector2f &ef_vector) const;
  124. // rotate a 2D vector from earth frame to body frame
  125. // in input, x is forward, y is right
  126. Vector2f rotate_body_to_earth2D(const Vector2f &bf) const;
  127. // return the average size of the roll/pitch error estimate
  128. // since last call
  129. float get_error_rp(void) const {
  130. return ahrs.get_error_rp();
  131. }
  132. // return the average size of the yaw error estimate
  133. // since last call
  134. float get_error_yaw(void) const {
  135. return ahrs.get_error_yaw();
  136. }
  137. float roll;
  138. float pitch;
  139. float yaw;
  140. int32_t roll_sensor;
  141. int32_t pitch_sensor;
  142. int32_t yaw_sensor;
  143. private:
  144. const enum Rotation rotation;
  145. AP_AHRS &ahrs;
  146. // body frame rotation for this View
  147. Matrix3f rot_view;
  148. // transpose of rot_view
  149. Matrix3f rot_view_T;
  150. Matrix3f rot_body_to_ned;
  151. Vector3f gyro;
  152. struct {
  153. float cos_roll;
  154. float cos_pitch;
  155. float cos_yaw;
  156. float sin_roll;
  157. float sin_pitch;
  158. float sin_yaw;
  159. } trig;
  160. float y_angle;
  161. float _pitch_trim_deg;
  162. };