mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
Plane: added EKF2 to parameters as EK2_*
This commit is contained in:
parent
053194fd51
commit
91f990af06
@ -1188,6 +1188,10 @@ const AP_Param::Info Plane::var_info[] PROGMEM = {
|
||||
// @Group: EKF_
|
||||
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
|
||||
GOBJECTN(EKF, NavEKF, "EKF_", NavEKF),
|
||||
|
||||
// @Group: EK2_
|
||||
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
||||
GOBJECTN(EKF2, NavEKF2, "EK2_", NavEKF2),
|
||||
#endif
|
||||
|
||||
// @Group: RSSI_
|
||||
|
@ -199,6 +199,7 @@ public:
|
||||
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group
|
||||
k_param_mission, // mission library
|
||||
k_param_serial_manager, // serial manager library
|
||||
k_param_NavEKF2, // EKF2
|
||||
|
||||
//
|
||||
// 150: Navigation parameters
|
||||
|
@ -79,6 +79,7 @@
|
||||
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
|
||||
#include <AP_TECS/AP_TECS.h>
|
||||
#include <AP_NavEKF/AP_NavEKF.h>
|
||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||
#include <AP_Mission/AP_Mission.h> // Mission command library
|
||||
|
||||
#include <AP_Notify/AP_Notify.h> // Notify library
|
||||
@ -208,7 +209,8 @@ private:
|
||||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF EKF{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, rangefinder, EKF};
|
||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, rangefinder, EKF, EKF2};
|
||||
#else
|
||||
AP_AHRS_DCM ahrs {ins, barometer, gps};
|
||||
#endif
|
||||
|
@ -38,6 +38,7 @@ LIBRARIES += AP_Vehicle
|
||||
LIBRARIES += AP_SpdHgtControl
|
||||
LIBRARIES += AP_TECS
|
||||
LIBRARIES += AP_NavEKF
|
||||
LIBRARIES += AP_NavEKF2
|
||||
LIBRARIES += AP_Mission
|
||||
LIBRARIES += AP_Notify
|
||||
LIBRARIES += AP_BattMonitor
|
||||
|
Loading…
Reference in New Issue
Block a user