AP_InertialNav.h 2.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  1. #pragma once
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
  4. /*
  5. * AP_InertialNav blends accelerometer data with gps and barometer data to improve altitude and position hold.
  6. *
  7. * Most of the functions have to be called at 100Hz. (see defines above)
  8. *
  9. * The accelerometer values are integrated over time to approximate velocity and position.
  10. * The inaccurcy of these estimates grows over time due to noisy sensor data.
  11. * To improve the accuracy, baro and gps readings are used:
  12. * An error value is calculated as the difference between the sensor's measurement and the last position estimation.
  13. * This value is weighted with a gain factor and incorporated into the new estimation
  14. *
  15. * Special thanks to Tony Lambregts (FAA) for advice which contributed to the development of this filter.
  16. *
  17. */
  18. class AP_InertialNav
  19. {
  20. public:
  21. // Constructor
  22. AP_InertialNav() {}
  23. /**
  24. * update - updates velocity and position estimates using latest info from accelerometers
  25. * augmented with gps and baro readings
  26. */
  27. virtual void update(void) = 0;
  28. /**
  29. * get_filter_status : returns filter status as a series of flags
  30. */
  31. virtual nav_filter_status get_filter_status() const = 0;
  32. //
  33. // XY Axis specific methods
  34. //
  35. /**
  36. * get_position - returns the current position relative to the home location in cm.
  37. *
  38. * @return
  39. */
  40. virtual const Vector3f& get_position() const = 0;
  41. /**
  42. * get_velocity - returns the current velocity in cm/s
  43. *
  44. * @return velocity vector:
  45. * .x : latitude velocity in cm/s
  46. * .y : longitude velocity in cm/s
  47. * .z : vertical velocity in cm/s
  48. */
  49. virtual const Vector3f& get_velocity() const = 0;
  50. /**
  51. * get_speed_xy - returns the current horizontal speed in cm/s
  52. *
  53. * @returns the current horizontal speed in cm/s
  54. */
  55. virtual float get_speed_xy() const = 0;
  56. //
  57. // Z Axis methods
  58. //
  59. /**
  60. * get_altitude - get latest altitude estimate in cm above the
  61. * reference position
  62. * @return
  63. */
  64. virtual float get_altitude() const = 0;
  65. /**
  66. * get_velocity_z - returns the current climbrate.
  67. *
  68. * @see get_velocity().z
  69. *
  70. * @return climbrate in cm/s (positive up)
  71. */
  72. virtual float get_velocity_z() const = 0;
  73. };
  74. #if AP_AHRS_NAVEKF_AVAILABLE
  75. #include "AP_InertialNav_NavEKF.h"
  76. #endif