diff --git a/ArduSub/APM_Config.h b/ArduSub/APM_Config.h index 4ce0516731..0640f3df0c 100644 --- a/ArduSub/APM_Config.h +++ b/ArduSub/APM_Config.h @@ -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) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index f6d57e6407..cbaaee40d0 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -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 diff --git a/ArduSub/flight_mode.cpp b/ArduSub/flight_mode.cpp index 4a8cf2ccc0..e082afdcdc 100644 --- a/ArduSub/flight_mode.cpp +++ b/ArduSub/flight_mode.cpp @@ -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();