Sub: disable transect mode, and hide associated params

This commit is contained in:
Jacob Walser 2016-10-11 16:34:29 -04:00 committed by Andrew Tridgell
parent 2cb2633764
commit e8f9b044ef
3 changed files with 7 additions and 0 deletions

View File

@ -31,6 +31,7 @@
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
#define PRECISION_LANDING DISABLED // enable precision landing using companion computer or IRLock sensor
#define TRANSECT_ENABLED DISABLED
// features below are disabled by default on all boards
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)

View File

@ -817,9 +817,11 @@ const AP_Param::Info Sub::var_info[] = {
// @User: Standard
GGROUP(p_pos_xy, "POS_XY_", AC_P),
#if TRANSECT_ENABLED == ENABLED
GGROUP(pid_crosstrack_control, "XTRACK_", AC_PID),
GGROUP(pid_heading_control, "HEAD_", AC_PID),
#endif
// variables not in the g class which contain EEPROM saved variables

View File

@ -67,9 +67,11 @@ bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
success = drift_init(ignore_checks);
break;
#if TRANSECT_ENABLED == ENABLED
case TRANSECT:
success = transect_init(ignore_checks);
break;
#endif
case FLIP:
success = flip_init(ignore_checks);
@ -184,9 +186,11 @@ void Sub::update_flight_mode()
drift_run();
break;
#if TRANSECT_ENABLED == ENABLED
case TRANSECT:
transect_run();
break;
#endif
case FLIP:
flip_run();