diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index e7ecb2f492..8345750958 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -97,7 +97,8 @@ public: k_param_fs_batt_mah, k_param_angle_rate_max, // remove k_param_rssi_range, - k_param_rc_feel_rp, // 40 + k_param_rc_feel_rp, + k_param_NavEKF, // 41 - Extended Kalman Filter Inertial Navigation Group // 65: AP_Limits Library k_param_limits = 65, // deprecated - remove diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index a2062939f7..ede67c0ea3 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -1011,6 +1011,12 @@ const AP_Param::Info var_info[] PROGMEM = { // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp GOBJECT(rcmap, "RCMAP_", RCMapper), +#if AP_AHRS_NAVEKF_AVAILABLE + // @Group: EKF_ + // @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp + GOBJECTN(ahrs.get_NavEKF(), NavEKF, "EKF_", NavEKF), +#endif + AP_VAREND };