mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_InertialNav: rename for AHRS restructuring
This commit is contained in:
parent
2bd8a45c58
commit
dbc24d5cd3
@ -83,5 +83,3 @@ public:
|
|||||||
*/
|
*/
|
||||||
virtual float get_velocity_z() const = 0;
|
virtual float get_velocity_z() const = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include "AP_InertialNav_NavEKF.h"
|
|
||||||
|
@ -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.h"
|
#include "AP_InertialNav_NavEKF.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
A wrapper around the AP_InertialNav class which uses the NavEKF
|
A wrapper around the AP_InertialNav class which uses the NavEKF
|
||||||
|
@ -6,12 +6,13 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#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_NavEKF : public AP_InertialNav
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// Constructor
|
// Constructor
|
||||||
AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs) :
|
AP_InertialNav_NavEKF(AP_AHRS &ahrs) :
|
||||||
AP_InertialNav(),
|
AP_InertialNav(),
|
||||||
_ahrs_ekf(ahrs)
|
_ahrs_ekf(ahrs)
|
||||||
{}
|
{}
|
||||||
@ -70,5 +71,5 @@ public:
|
|||||||
private:
|
private:
|
||||||
Vector3f _relpos_cm; // NEU
|
Vector3f _relpos_cm; // NEU
|
||||||
Vector3f _velocity_cm; // NEU
|
Vector3f _velocity_cm; // NEU
|
||||||
AP_AHRS_NavEKF &_ahrs_ekf;
|
AP_AHRS &_ahrs_ekf;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user