AP_InertialNav_NavEKF.cpp 2.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_InertialNav.h"
  3. #if AP_AHRS_NAVEKF_AVAILABLE
  4. /*
  5. A wrapper around the AP_InertialNav class which uses the NavEKF
  6. filter if available, and falls back to the AP_InertialNav filter
  7. when EKF is not available
  8. */
  9. /**
  10. update internal state
  11. */
  12. void AP_InertialNav_NavEKF::update()
  13. {
  14. // get the NE position relative to the local earth frame origin
  15. Vector2f posNE;
  16. if (_ahrs_ekf.get_relative_position_NE_origin(posNE)) {
  17. _relpos_cm.x = posNE.x * 100; // convert from m to cm
  18. _relpos_cm.y = posNE.y * 100; // convert from m to cm
  19. }
  20. // get the D position relative to the local earth frame origin
  21. float posD;
  22. if (_ahrs_ekf.get_relative_position_D_origin(posD)) {
  23. _relpos_cm.z = - posD * 100; // convert from m in NED to cm in NEU
  24. }
  25. // get the velocity relative to the local earth frame
  26. Vector3f velNED;
  27. if (_ahrs_ekf.get_velocity_NED(velNED)) {
  28. _velocity_cm = velNED * 100; // convert to cm/s
  29. _velocity_cm.z = -_velocity_cm.z; // convert from NED to NEU
  30. }
  31. }
  32. /**
  33. * get_filter_status : returns filter status as a series of flags
  34. */
  35. nav_filter_status AP_InertialNav_NavEKF::get_filter_status() const
  36. {
  37. nav_filter_status status;
  38. _ahrs_ekf.get_filter_status(status);
  39. return status;
  40. }
  41. /**
  42. * get_position - returns the current position relative to the home location in cm.
  43. *
  44. * @return
  45. */
  46. const Vector3f &AP_InertialNav_NavEKF::get_position(void) const
  47. {
  48. return _relpos_cm;
  49. }
  50. /**
  51. * get_velocity - returns the current velocity in cm/s
  52. *
  53. * @return velocity vector:
  54. * .x : latitude velocity in cm/s
  55. * .y : longitude velocity in cm/s
  56. * .z : vertical velocity in cm/s
  57. */
  58. const Vector3f &AP_InertialNav_NavEKF::get_velocity() const
  59. {
  60. return _velocity_cm;
  61. }
  62. /**
  63. * get_speed_xy - returns the current horizontal speed in cm/s
  64. *
  65. * @returns the current horizontal speed in cm/s
  66. */
  67. float AP_InertialNav_NavEKF::get_speed_xy() const
  68. {
  69. return norm(_velocity_cm.x, _velocity_cm.y);
  70. }
  71. /**
  72. * get_altitude - get latest altitude estimate in cm
  73. * @return
  74. */
  75. float AP_InertialNav_NavEKF::get_altitude() const
  76. {
  77. return _relpos_cm.z;
  78. }
  79. /**
  80. * get_velocity_z - returns the current climbrate.
  81. *
  82. * @see get_velocity().z
  83. *
  84. * @return climbrate in cm/s
  85. */
  86. float AP_InertialNav_NavEKF::get_velocity_z() const
  87. {
  88. return _velocity_cm.z;
  89. }
  90. #endif // AP_AHRS_NAVEKF_AVAILABLE