diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index b5d40402e3..b19906fc55 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -97,7 +97,8 @@ public: k_param_gpslock_limit, // deprecated - remove k_param_geofence_limit, // deprecated - remove k_param_altitude_limit, // deprecated - remove - k_param_fence, // 69 + k_param_fence, + k_param_gps_glitch, // 70 // // 80: Heli diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 91705f93b8..8ae57bd22d 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -1039,6 +1039,10 @@ const AP_Param::Info var_info[] PROGMEM = { GOBJECT(fence, "FENCE_", AC_Fence), #endif + // @Group: GPSGLITCH_ + // @Path: ../libraries/AP_GPS/AP_GPS_Glitch.cpp + GOBJECT(gps_glitch, "GPSGLITCH_", GPS_Glitch), + #if FRAME_CONFIG == HELI_FRAME // @Group: H_ // @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp