mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
Sub: Hide Circle Nav parameters from user
This commit is contained in:
parent
0d575681de
commit
e66ba2ad74
@ -750,9 +750,11 @@ const AP_Param::Info Sub::var_info[] = {
|
|||||||
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
|
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
|
||||||
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
|
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
|
||||||
|
|
||||||
|
#if CIRCLE_NAV_ENABLED == ENABLED
|
||||||
// @Group: CIRCLE_
|
// @Group: CIRCLE_
|
||||||
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
|
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
|
||||||
GOBJECT(circle_nav, "CIRCLE_", AC_Circle),
|
GOBJECT(circle_nav, "CIRCLE_", AC_Circle),
|
||||||
|
#endif
|
||||||
|
|
||||||
// @Group: ATC_
|
// @Group: ATC_
|
||||||
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
|
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
|
||||||
|
@ -86,6 +86,14 @@
|
|||||||
# define RC_FAST_SPEED 490
|
# define RC_FAST_SPEED 490
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Circle Nav parameters
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef CIRCLE_NAV_ENABLED
|
||||||
|
# define CIRCLE_NAV_ENABLED DISABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Channel 6 Tuning
|
// Channel 6 Tuning
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user