APM:Libraries
AP_InertialNav.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_AHRS/AP_AHRS.h>
4 #include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega IMU Library
5 #include <AP_Baro/AP_Baro.h> // ArduPilot Mega Barometer Library
6 #include <AP_Buffer/AP_Buffer.h> // FIFO buffer library
7 #include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
8 
9 /*
10  * AP_InertialNav blends accelerometer data with gps and barometer data to improve altitude and position hold.
11  *
12  * Most of the functions have to be called at 100Hz. (see defines above)
13  *
14  * The accelerometer values are integrated over time to approximate velocity and position.
15  * The inaccurcy of these estimates grows over time due to noisy sensor data.
16  * To improve the accuracy, baro and gps readings are used:
17  * An error value is calculated as the difference between the sensor's measurement and the last position estimation.
18  * This value is weighted with a gain factor and incorporated into the new estimation
19  *
20  * Special thanks to Tony Lambregts (FAA) for advice which contributed to the development of this filter.
21  *
22  */
24 {
25 public:
26 
27  // Constructor
29 
36  virtual void update(float dt) = 0;
37 
41  virtual nav_filter_status get_filter_status() const = 0;
42 
48  virtual struct Location get_origin() const = 0;
49 
50  //
51  // XY Axis specific methods
52  //
53 
59  virtual const Vector3f& get_position() const = 0;
60 
65  virtual bool get_location(struct Location &loc) const = 0;
66 
71  virtual int32_t get_latitude() const = 0;
72 
77  virtual int32_t get_longitude() const = 0;
78 
87  virtual const Vector3f& get_velocity() const = 0;
88 
94  virtual float get_velocity_xy() const = 0;
95 
96  //
97  // Z Axis methods
98  //
99 
105  virtual float get_altitude() const = 0;
106 
114  virtual float get_velocity_z() const = 0;
115 };
116 
117 #if AP_AHRS_NAVEKF_AVAILABLE
118 #include "AP_InertialNav_NavEKF.h"
119 #endif
virtual bool get_location(struct Location &loc) const =0
virtual float get_velocity_z() const =0
virtual const Vector3f & get_position() const =0
virtual nav_filter_status get_filter_status() const =0
virtual int32_t get_longitude() const =0
virtual int32_t get_latitude() const =0
virtual void update(float dt)=0
virtual float get_velocity_xy() const =0
virtual const Vector3f & get_velocity() const =0
virtual float get_altitude() const =0
fifo (queue) buffer template class