diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 3ff8427bed..7a00567aef 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -108,6 +108,7 @@ public: // 100: Inertial Nav // k_param_inertial_nav = 100, + k_param_wp_nav = 101, // 110: Telemetry control // diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index f6bcf2ec29..bc95c8f520 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -958,6 +958,10 @@ const AP_Param::Info var_info[] PROGMEM = { // @Path: ../libraries/AP_InertialNav/AP_InertialNav.cpp GOBJECT(inertial_nav, "INAV_", AP_InertialNav), + //@Group: WPNAV_ + //@Path: ../libraries/AC_WPNav/AC_WPNav.cpp + GOBJECT(wp_nav, "WPNAV_", AC_WPNav), + // @Group: SR0_ // @Path: ./GCS_Mavlink.pde GOBJECT(gcs0, "SR0_", GCS_MAVLINK),