AP_NavEKF : Mavlink tunable parameter - first attempt
This commit is contained in:
parent
8c4b0b9be9
commit
f0f76920fa
@ -21,6 +21,19 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
#define earthRate 0.000072921f // earth rotation rate (rad/sec)
|
#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
|
// constructor
|
||||||
NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
|
NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
|
||||||
_ahrs(ahrs),
|
_ahrs(ahrs),
|
||||||
|
@ -26,6 +26,7 @@
|
|||||||
#include <AP_Baro.h>
|
#include <AP_Baro.h>
|
||||||
#include <AP_Airspeed.h>
|
#include <AP_Airspeed.h>
|
||||||
#include <AP_Compass.h>
|
#include <AP_Compass.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
|
|
||||||
// #define MATH_CHECK_INDEXES 1
|
// #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
|
uint32_t _hgtRetryTimeMode12; // height measurement retry time following innovation consistency fail if GPS fusion mode is > 0
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
// EKF tuneable parameters
|
||||||
|
AP_Float _blah;
|
||||||
|
|
||||||
bool statesInitialised; // boolean true when filter states have been initialised
|
bool statesInitialised; // boolean true when filter states have been initialised
|
||||||
bool staticModeDemanded; // boolean true when staticMode has been demanded externally.
|
bool staticModeDemanded; // boolean true when staticMode has been demanded externally.
|
||||||
bool velHealth; // boolean true if velocity measurements have failed innovation consistency check
|
bool velHealth; // boolean true if velocity measurements have failed innovation consistency check
|
||||||
|
Loading…
Reference in New Issue
Block a user