Plane : NavEKF Mavlink tunable parameter - first attempt
This commit is contained in:
parent
128f71157d
commit
8c4b0b9be9
@ -153,6 +153,9 @@ public:
|
||||
k_param_barometer, // barometer ground calibration
|
||||
k_param_airspeed, // AP_Airspeed parameters
|
||||
k_param_curr_amp_offset,
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group
|
||||
#endif
|
||||
|
||||
//
|
||||
// 150: Navigation parameters
|
||||
|
@ -973,6 +973,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(obc, "FS_", APM_OBC),
|
||||
#endif
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
// @Group: EKF_
|
||||
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
|
||||
GOBJECT(NavEKF, "EKF_", AP_NavEKF),
|
||||
#endif
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user