AP_AHRS_View.cpp 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * AHRS View class - for creating a 2nd view of the vehicle attitude
  15. *
  16. */
  17. #include "AP_AHRS_View.h"
  18. #include <stdio.h>
  19. AP_AHRS_View::AP_AHRS_View(AP_AHRS &_ahrs, enum Rotation _rotation, float pitch_trim_deg) :
  20. rotation(_rotation),
  21. ahrs(_ahrs)
  22. {
  23. switch (rotation) {
  24. case ROTATION_NONE:
  25. y_angle = 0;
  26. break;
  27. case ROTATION_PITCH_90:
  28. y_angle = 90;
  29. break;
  30. case ROTATION_PITCH_270:
  31. y_angle = 270;
  32. break;
  33. default:
  34. AP_HAL::panic("Unsupported AHRS view %u\n", (unsigned)rotation);
  35. }
  36. _pitch_trim_deg = pitch_trim_deg;
  37. // Add pitch trim
  38. rot_view.from_euler(0, radians(wrap_360(y_angle + pitch_trim_deg)), 0);
  39. rot_view_T = rot_view;
  40. rot_view_T.transpose();
  41. // setup initial state
  42. update();
  43. }
  44. // apply pitch trim
  45. void AP_AHRS_View::set_pitch_trim(float trim_deg) {
  46. _pitch_trim_deg = trim_deg;
  47. rot_view.from_euler(0, radians(wrap_360(y_angle + _pitch_trim_deg)), 0);
  48. rot_view_T = rot_view;
  49. rot_view_T.transpose();
  50. };
  51. // update state
  52. void AP_AHRS_View::update(bool skip_ins_update)
  53. {
  54. rot_body_to_ned = ahrs.get_rotation_body_to_ned();
  55. gyro = ahrs.get_gyro();
  56. if (!is_zero(y_angle + _pitch_trim_deg)) {
  57. rot_body_to_ned = rot_body_to_ned * rot_view_T;
  58. gyro = rot_view * gyro;
  59. }
  60. rot_body_to_ned.to_euler(&roll, &pitch, &yaw);
  61. roll_sensor = degrees(roll) * 100;
  62. pitch_sensor = degrees(pitch) * 100;
  63. yaw_sensor = degrees(yaw) * 100;
  64. if (yaw_sensor < 0) {
  65. yaw_sensor += 36000;
  66. }
  67. ahrs.calc_trig(rot_body_to_ned,
  68. trig.cos_roll, trig.cos_pitch, trig.cos_yaw,
  69. trig.sin_roll, trig.sin_pitch, trig.sin_yaw);
  70. }
  71. // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
  72. Vector3f AP_AHRS_View::get_gyro_latest(void) const {
  73. Vector3f gyro_latest = ahrs.get_gyro_latest();
  74. gyro_latest.rotate(rotation);
  75. return gyro_latest;
  76. }
  77. // rotate a 2D vector from earth frame to body frame
  78. Vector2f AP_AHRS_View::rotate_earth_to_body2D(const Vector2f &ef) const
  79. {
  80. return Vector2f(ef.x * trig.cos_yaw + ef.y * trig.sin_yaw,
  81. -ef.x * trig.sin_yaw + ef.y * trig.cos_yaw);
  82. }
  83. // rotate a 2D vector from earth frame to body frame
  84. Vector2f AP_AHRS_View::rotate_body_to_earth2D(const Vector2f &bf) const
  85. {
  86. return Vector2f(bf.x * trig.cos_yaw - bf.y * trig.sin_yaw,
  87. bf.x * trig.sin_yaw + bf.y * trig.cos_yaw);
  88. }