1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374 |
- #pragma once
- #include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
- class AP_InertialNav_NavEKF : public AP_InertialNav
- {
- public:
-
- AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs) :
- AP_InertialNav(),
- _ahrs_ekf(ahrs)
- {}
-
- void update() override;
-
- nav_filter_status get_filter_status() const override;
-
- const Vector3f& get_position() const override;
-
- const Vector3f& get_velocity() const override;
-
- float get_speed_xy() const override;
-
- float get_altitude() const override;
-
- float get_velocity_z() const override;
- private:
- Vector3f _relpos_cm;
- Vector3f _velocity_cm;
- AP_AHRS_NavEKF &_ahrs_ekf;
- };
|