mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
Sub: Disable TRANSECT parameters
This commit is contained in:
parent
6426ceec27
commit
eeadfa0d92
@ -29,7 +29,6 @@
|
|||||||
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
||||||
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
||||||
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
|
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
|
||||||
#define TRANSECT_ENABLED DISABLED
|
|
||||||
|
|
||||||
// features below are disabled by default on all boards
|
// features below are disabled by default on all boards
|
||||||
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
||||||
|
@ -448,9 +448,10 @@ public:
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#if TRANSECT_ENABLED == ENABLED
|
||||||
AC_PID pid_crosstrack_control;
|
AC_PID pid_crosstrack_control;
|
||||||
AC_PID pid_heading_control;
|
AC_PID pid_heading_control;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// Autotune
|
// Autotune
|
||||||
@ -492,11 +493,13 @@ public:
|
|||||||
//----------------------------------------------------------------------
|
//----------------------------------------------------------------------
|
||||||
p_pos_xy (POS_XY_P),
|
p_pos_xy (POS_XY_P),
|
||||||
|
|
||||||
p_alt_hold (ALT_HOLD_P),
|
p_alt_hold (ALT_HOLD_P)
|
||||||
|
|
||||||
|
#if TRANSECT_ENABLED == ENABLED
|
||||||
|
,
|
||||||
pid_crosstrack_control (XTRACK_P, XTRACK_I, XTRACK_D, XTRACK_IMAX, XTRACK_FILT_HZ, XTRACK_DT),
|
pid_crosstrack_control (XTRACK_P, XTRACK_I, XTRACK_D, XTRACK_IMAX, XTRACK_FILT_HZ, XTRACK_DT),
|
||||||
|
|
||||||
pid_heading_control (HEAD_P, HEAD_I, HEAD_D, HEAD_IMAX, HEAD_FILT_HZ, HEAD_DT)
|
pid_heading_control (HEAD_P, HEAD_I, HEAD_D, HEAD_IMAX, HEAD_FILT_HZ, HEAD_DT)
|
||||||
|
#endif
|
||||||
|
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
@ -102,6 +102,14 @@
|
|||||||
# define RCMAP_ENABLED DISABLED
|
# define RCMAP_ENABLED DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Experimental transect modes
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef TRANSECT_ENABLED
|
||||||
|
# define TRANSECT_ENABLED DISABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Rangefinder
|
// Rangefinder
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user