GCS_MAVLink: add capability to send autopilot to config error loop
[ardupilot.git] / ArduCopter / APM_Config.h
blob7f1ecabb7f14c6bfc0f3c3a0695b78b8f7067b57
1 // User specific config file. Any items listed in config.h can be overridden here.
3 // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
4 //#define LOGGING_ENABLED 0 // disable logging to save 11K of flash space
5 //#define MOUNT 0 // disable the camera gimbal to save 8K of flash space
6 //#define AUTOTUNE_ENABLED 0 // disable the auto tune functionality to save 7k of flash
7 //#define NAV_GUIDED 0 // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
8 //#define MODE_ACRO_ENABLED 0 // disable acrobatic mode support
9 //#define MODE_AUTO_ENABLED 0 // disable auto mode support
10 //#define MODE_BRAKE_ENABLED 0 // disable brake mode support
11 //#define MODE_CIRCLE_ENABLED 0 // disable circle mode support
12 //#define MODE_DRIFT_ENABLED 0 // disable drift mode support
13 //#define MODE_FLIP_ENABLED 0 // disable flip mode support
14 //#define MODE_FOLLOW_ENABLED 0 // disable follow mode support
15 //#define MODE_GUIDED_ENABLED 0 // disable guided mode support
16 //#define MODE_GUIDED_NOGPS_ENABLED 0 // disable guided/nogps mode support
17 //#define MODE_LOITER_ENABLED 0 // disable loiter mode support
18 //#define MODE_POSHOLD_ENABLED 0 // disable poshold mode support
19 //#define MODE_RTL_ENABLED 0 // disable rtl mode support
20 //#define MODE_SMARTRTL_ENABLED 0 // disable smartrtl mode support
21 //#define MODE_SPORT_ENABLED 0 // disable sport mode support
22 //#define MODE_SYSTEMID_ENABLED 0 // disable system ID mode support
23 //#define MODE_THROW_ENABLED 0 // disable throw mode support
24 //#define MODE_ZIGZAG_ENABLED 0 // disable zigzag mode support
25 //#define OSD_ENABLED 0 // disable on-screen-display support
27 // features below are disabled by default on all boards
28 //#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
29 //#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
30 //#define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events
32 // other settings
33 //#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
35 // User Hooks : For User Developed code that you wish to run
36 // Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
37 //#define USERHOOK_VARIABLES "UserVariables.h"
38 // Put your custom code into the UserCode.cpp with function names matching those listed below and ensure the appropriate #define below is uncommented below
39 //#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
40 //#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
41 //#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
42 //#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
43 //#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
44 //#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
45 //#define USERHOOK_AUXSWITCH 1 // for code to handle user aux switches
46 //#define USER_PARAMS_ENABLED 1 // to enable user parameters