AP_InertialNav_NavEKF.h 1.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374
  1. /*
  2. A wrapper around the AP_InertialNav class which uses the NavEKF
  3. filter if available, and falls back to the AP_InertialNav filter
  4. when EKF is not available
  5. */
  6. #pragma once
  7. #include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
  8. class AP_InertialNav_NavEKF : public AP_InertialNav
  9. {
  10. public:
  11. // Constructor
  12. AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs) :
  13. AP_InertialNav(),
  14. _ahrs_ekf(ahrs)
  15. {}
  16. /**
  17. update internal state
  18. */
  19. void update() override;
  20. /**
  21. * get_filter_status - returns filter status as a series of flags
  22. */
  23. nav_filter_status get_filter_status() const override;
  24. /**
  25. * get_position - returns the current position relative to the home location in cm.
  26. *
  27. * the home location was set with AP_InertialNav::set_home_position(int32_t, int32_t)
  28. *
  29. * @return
  30. */
  31. const Vector3f& get_position() const override;
  32. /**
  33. * get_velocity - returns the current velocity in cm/s
  34. *
  35. * @return velocity vector:
  36. * .x : latitude velocity in cm/s
  37. * .y : longitude velocity in cm/s
  38. * .z : vertical velocity in cm/s
  39. */
  40. const Vector3f& get_velocity() const override;
  41. /**
  42. * get_speed_xy - returns the current horizontal speed in cm/s
  43. *
  44. * @returns the current horizontal speed in cm/s
  45. */
  46. float get_speed_xy() const override;
  47. /**
  48. * get_altitude - get latest altitude estimate in cm
  49. * @return
  50. */
  51. float get_altitude() const override;
  52. /**
  53. * get_velocity_z - returns the current climbrate.
  54. *
  55. * @see get_velocity().z
  56. *
  57. * @return climbrate in cm/s
  58. */
  59. float get_velocity_z() const override;
  60. private:
  61. Vector3f _relpos_cm; // NEU
  62. Vector3f _velocity_cm; // NEU
  63. AP_AHRS_NavEKF &_ahrs_ekf;
  64. };