diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 13564d8296..5b984d2e13 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -21,6 +21,19 @@ extern const AP_HAL::HAL& hal; #define earthRate 0.000072921f // earth rotation rate (rad/sec) +// Define tuning parameters +const AP_Param::GroupInfo AP_NavEKF::var_info[] PROGMEM = { + + // @Param: TEST PARAM + // @DisplayName: Blah (units) + // @Description: Blah blah. + // @Increment: 0.1 + // @User: advanced + AP_GROUPINFO("BLAH", 0, AP_NavEKF, _blah, 1.0f), + + AP_GROUPEND +}; + // constructor NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) : _ahrs(ahrs), diff --git a/libraries/AP_NavEKF/AP_NavEKF.h b/libraries/AP_NavEKF/AP_NavEKF.h index 15f6f2f828..235e3e04db 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.h +++ b/libraries/AP_NavEKF/AP_NavEKF.h @@ -26,6 +26,7 @@ #include #include #include +#include // #define MATH_CHECK_INDEXES 1 @@ -254,6 +255,9 @@ public: uint32_t _hgtRetryTimeMode12; // height measurement retry time following innovation consistency fail if GPS fusion mode is > 0 private: + // EKF tuneable parameters + AP_Float _blah; + bool statesInitialised; // boolean true when filter states have been initialised bool staticModeDemanded; // boolean true when staticMode has been demanded externally. bool velHealth; // boolean true if velocity measurements have failed innovation consistency check