APM:Libraries
AP_InertialNav_NavEKF.h
Go to the documentation of this file.
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 
8 #include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
9 
11 {
12 public:
13  // Constructor
16  _haveabspos(false),
17  _ahrs_ekf(ahrs)
18  {}
19 
23  void update(float dt);
24 
29 
35  struct Location get_origin() const;
36 
44  const Vector3f& get_position() const;
45 
50  bool get_location(struct Location &loc) const;
51 
55  int32_t get_latitude() const;
56 
61  int32_t get_longitude() const;
62 
71  const Vector3f& get_velocity() const;
72 
76  float get_pos_z_derivative() const;
77 
83  float get_velocity_xy() const;
84 
89  float get_altitude() const;
90 
98  float get_velocity_z() const;
99 
100 private:
103  float _pos_z_rate;
107 };
float get_velocity_z() const
float get_altitude() const
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float get_pos_z_derivative() const
const Vector3f & get_position() const
const Vector3f & get_velocity() const
nav_filter_status get_filter_status() const
int32_t get_latitude() const
void update(float dt)
AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs)
float get_velocity_xy() const
int32_t get_longitude() const
bool get_location(struct Location &loc) const