AP_InertialNav: handle renaming of AP_InertialNav_NavEKF to AP_InertialNav

This commit is contained in:
Peter Barker 2021-10-19 13:15:00 +11:00 committed by Andrew Tridgell
parent 300628a570
commit cf9f060db8
2 changed files with 18 additions and 19 deletions

View File

@ -1,6 +1,6 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Baro/AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include "AP_InertialNav_NavEKF.h" #include "AP_InertialNav.h"
/* /*
A wrapper around the AP_InertialNav class which uses the NavEKF A wrapper around the AP_InertialNav class which uses the NavEKF
@ -11,7 +11,7 @@
/** /**
update internal state update internal state
*/ */
void AP_InertialNav_NavEKF::update(bool high_vibes) void AP_InertialNav::update(bool high_vibes)
{ {
// get the NE position relative to the local earth frame origin // get the NE position relative to the local earth frame origin
Vector2f posNE; Vector2f posNE;
@ -44,7 +44,7 @@ void AP_InertialNav_NavEKF::update(bool high_vibes)
/** /**
* get_filter_status : returns filter status as a series of flags * get_filter_status : returns filter status as a series of flags
*/ */
nav_filter_status AP_InertialNav_NavEKF::get_filter_status() const nav_filter_status AP_InertialNav::get_filter_status() const
{ {
nav_filter_status status; nav_filter_status status;
_ahrs_ekf.get_filter_status(status); _ahrs_ekf.get_filter_status(status);
@ -56,7 +56,7 @@ nav_filter_status AP_InertialNav_NavEKF::get_filter_status() const
* *
* @return * @return
*/ */
const Vector3f &AP_InertialNav_NavEKF::get_position(void) const const Vector3f &AP_InertialNav::get_position(void) const
{ {
return _relpos_cm; return _relpos_cm;
} }
@ -69,7 +69,7 @@ const Vector3f &AP_InertialNav_NavEKF::get_position(void) const
* .y : longitude velocity in cm/s * .y : longitude velocity in cm/s
* .z : vertical velocity in cm/s * .z : vertical velocity in cm/s
*/ */
const Vector3f &AP_InertialNav_NavEKF::get_velocity() const const Vector3f &AP_InertialNav::get_velocity() const
{ {
return _velocity_cm; return _velocity_cm;
} }
@ -79,7 +79,7 @@ const Vector3f &AP_InertialNav_NavEKF::get_velocity() const
* *
* @returns the current horizontal speed in cm/s * @returns the current horizontal speed in cm/s
*/ */
float AP_InertialNav_NavEKF::get_speed_xy() const float AP_InertialNav::get_speed_xy() const
{ {
return _velocity_cm.xy().length(); return _velocity_cm.xy().length();
} }
@ -88,7 +88,7 @@ float AP_InertialNav_NavEKF::get_speed_xy() const
* get_altitude - get latest altitude estimate in cm * get_altitude - get latest altitude estimate in cm
* @return * @return
*/ */
float AP_InertialNav_NavEKF::get_altitude() const float AP_InertialNav::get_altitude() const
{ {
return _relpos_cm.z; return _relpos_cm.z;
} }
@ -100,7 +100,7 @@ float AP_InertialNav_NavEKF::get_altitude() const
* *
* @return climbrate in cm/s * @return climbrate in cm/s
*/ */
float AP_InertialNav_NavEKF::get_velocity_z() const float AP_InertialNav::get_velocity_z() const
{ {
return _velocity_cm.z; return _velocity_cm.z;
} }

View File

@ -5,27 +5,26 @@
*/ */
#pragma once #pragma once
#include <AP_AHRS/AP_AHRS.h>
#include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters #include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
#include "AP_InertialNav.h"
class AP_InertialNav_NavEKF : public AP_InertialNav class AP_InertialNav
{ {
public: public:
// Constructor // Constructor
AP_InertialNav_NavEKF(AP_AHRS &ahrs) : AP_InertialNav(AP_AHRS &ahrs) :
AP_InertialNav(),
_ahrs_ekf(ahrs) _ahrs_ekf(ahrs)
{} {}
/** /**
update internal state update internal state
*/ */
void update(bool high_vibes = false) override; void update(bool high_vibes = false);
/** /**
* get_filter_status - returns filter status as a series of flags * get_filter_status - returns filter status as a series of flags
*/ */
nav_filter_status get_filter_status() const override; nav_filter_status get_filter_status() const;
/** /**
* get_position - returns the current position relative to the home location in cm. * get_position - returns the current position relative to the home location in cm.
@ -34,7 +33,7 @@ public:
* *
* @return * @return
*/ */
const Vector3f& get_position() const override; const Vector3f& get_position() const;
/** /**
* get_velocity - returns the current velocity in cm/s * get_velocity - returns the current velocity in cm/s
@ -44,20 +43,20 @@ public:
* .y : longitude velocity in cm/s * .y : longitude velocity in cm/s
* .z : vertical velocity in cm/s * .z : vertical velocity in cm/s
*/ */
const Vector3f& get_velocity() const override; const Vector3f& get_velocity() const;
/** /**
* get_speed_xy - returns the current horizontal speed in cm/s * get_speed_xy - returns the current horizontal speed in cm/s
* *
* @returns the current horizontal speed in cm/s * @returns the current horizontal speed in cm/s
*/ */
float get_speed_xy() const override; float get_speed_xy() const;
/** /**
* get_altitude - get latest altitude estimate in cm * get_altitude - get latest altitude estimate in cm
* @return * @return
*/ */
float get_altitude() const override; float get_altitude() const;
/** /**
* get_velocity_z - returns the current climbrate. * get_velocity_z - returns the current climbrate.
@ -66,7 +65,7 @@ public:
* *
* @return climbrate in cm/s * @return climbrate in cm/s
*/ */
float get_velocity_z() const override; float get_velocity_z() const;
private: private:
Vector3f _relpos_cm; // NEU Vector3f _relpos_cm; // NEU