APM:Copter
config.h
Go to the documentation of this file.
1 //
2 #pragma once
3 
6 //
7 // WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
8 //
9 // DO NOT EDIT this file to adjust your configuration. Create your own
10 // APM_Config.h and use APM_Config.h.example as a reference.
11 //
12 // WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
16 //
17 // Default and automatic configuration details.
18 //
19 // Notes for maintainers:
20 //
21 // - Try to keep this file organised in the same order as APM_Config.h.example
22 //
23 #include "defines.h"
24 
29 #include "APM_Config.h"
30 
31 
34 // HARDWARE CONFIGURATION AND CONNECTIONS
37 
38 #ifndef CONFIG_HAL_BOARD
39 #error CONFIG_HAL_BOARD must be defined to build ArduCopter
40 #endif
41 
43 // HIL_MODE OPTIONAL
44 
45 #ifndef HIL_MODE
46  #define HIL_MODE HIL_MODE_DISABLED
47 #endif
48 
49 #define MAGNETOMETER ENABLED
50 
51 #ifndef ARMING_DELAY_SEC
52  # define ARMING_DELAY_SEC 2.0f
53 #endif
54 
56 // FRAME_CONFIG
57 //
58 #ifndef FRAME_CONFIG
59  # define FRAME_CONFIG MULTICOPTER_FRAME
60 #endif
61 
63 // TradHeli defaults
64 #if FRAME_CONFIG == HELI_FRAME
65  # define RC_FAST_SPEED 125
66  # define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD
67  # define THR_MIN_DEFAULT 0
68  # define AUTOTUNE_ENABLED DISABLED
69  # define ACCEL_Z_P 0.30f
70 #endif
71 
73 // PWM control
74 // default RC speed in Hz
75 #ifndef RC_FAST_SPEED
76  # define RC_FAST_SPEED 490
77 #endif
78 
80 // Rangefinder
81 //
82 
83 #ifndef RANGEFINDER_ENABLED
84  # define RANGEFINDER_ENABLED ENABLED
85 #endif
86 
87 #ifndef RANGEFINDER_HEALTH_MAX
88  # define RANGEFINDER_HEALTH_MAX 3 // number of good reads that indicates a healthy rangefinder
89 #endif
90 
91 #ifndef RANGEFINDER_GAIN_DEFAULT
92  # define RANGEFINDER_GAIN_DEFAULT 0.8f // gain for controlling how quickly rangefinder range adjusts target altitude (lower means slower reaction)
93 #endif
94 
95 #ifndef THR_SURFACE_TRACKING_VELZ_MAX
96  # define THR_SURFACE_TRACKING_VELZ_MAX 150 // max vertical speed change while surface tracking with rangefinder
97 #endif
98 
99 #ifndef RANGEFINDER_TIMEOUT_MS
100  # define RANGEFINDER_TIMEOUT_MS 1000 // desired rangefinder alt will reset to current rangefinder alt after this many milliseconds without a good rangefinder alt
101 #endif
102 
103 #ifndef RANGEFINDER_WPNAV_FILT_HZ
104  # define RANGEFINDER_WPNAV_FILT_HZ 0.25f // filter frequency for rangefinder altitude provided to waypoint navigation class
105 #endif
106 
107 #ifndef RANGEFINDER_TILT_CORRECTION // by disable tilt correction for use of range finder data by EKF
108  # define RANGEFINDER_TILT_CORRECTION ENABLED
109 #endif
110 
111 #ifndef RANGEFINDER_GLITCH_ALT_CM
112  # define RANGEFINDER_GLITCH_ALT_CM 200 // amount of rangefinder change to be considered a glitch
113 #endif
114 
115 #ifndef RANGEFINDER_GLITCH_NUM_SAMPLES
116  # define RANGEFINDER_GLITCH_NUM_SAMPLES 3 // number of rangefinder glitches in a row to take new reading
117 #endif
118 
120 // Proximity sensor
121 //
122 #ifndef PROXIMITY_ENABLED
123  # define PROXIMITY_ENABLED ENABLED
124 #endif
125 
126 #ifndef MAV_SYSTEM_ID
127  # define MAV_SYSTEM_ID 1
128 #endif
129 
130 
132 // Battery monitoring
133 //
134 #ifndef BOARD_VOLTAGE_MIN
135  # define BOARD_VOLTAGE_MIN 4.3f // min board voltage in volts for pre-arm checks
136 #endif
137 
138 #ifndef BOARD_VOLTAGE_MAX
139  # define BOARD_VOLTAGE_MAX 5.8f // max board voltage in volts for pre-arm checks
140 #endif
141 
142 // prearm GPS hdop check
143 #ifndef GPS_HDOP_GOOD_DEFAULT
144  # define GPS_HDOP_GOOD_DEFAULT 140 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled
145 #endif
146 
147 // GCS failsafe
148 #ifndef FS_GCS
149  # define FS_GCS DISABLED
150 #endif
151 #ifndef FS_GCS_TIMEOUT_MS
152  # define FS_GCS_TIMEOUT_MS 5000 // gcs failsafe triggers after 5 seconds with no GCS heartbeat
153 #endif
154 
155 // Radio failsafe while using RC_override
156 #ifndef FS_RADIO_RC_OVERRIDE_TIMEOUT_MS
157  # define FS_RADIO_RC_OVERRIDE_TIMEOUT_MS 1000 // RC Radio failsafe triggers after 1 second while using RC_override from ground station
158 #endif
159 
160 // Radio failsafe
161 #ifndef FS_RADIO_TIMEOUT_MS
162  #define FS_RADIO_TIMEOUT_MS 500 // RC Radio Failsafe triggers after 500 miliseconds with No RC Input
163 #endif
164 
165 // missing terrain data failsafe
166 #ifndef FS_TERRAIN_TIMEOUT_MS
167  #define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL)
168 #endif
169 
170 #ifndef PREARM_DISPLAY_PERIOD
171 # define PREARM_DISPLAY_PERIOD 30
172 #endif
173 
174 // pre-arm baro vs inertial nav max alt disparity
175 #ifndef PREARM_MAX_ALT_DISPARITY_CM
176  # define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters
177 #endif
178 
180 // EKF Failsafe
181 #ifndef FS_EKF_ACTION_DEFAULT
182  # define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_LAND // EKF failsafe triggers land by default
183 #endif
184 #ifndef FS_EKF_THRESHOLD_DEFAULT
185  # define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered
186 #endif
187 
188 #ifndef EKF_ORIGIN_MAX_DIST_M
189  # define EKF_ORIGIN_MAX_DIST_M 50000 // EKF origin and waypoints (including home) must be within 50km
190 #endif
191 
193 // MAGNETOMETER
194 #ifndef MAGNETOMETER
195  # define MAGNETOMETER ENABLED
196 #endif
197 
198 #ifndef COMPASS_CAL_STICK_GESTURE_TIME
199  #define COMPASS_CAL_STICK_GESTURE_TIME 2.0f // 2 seconds
200 #endif
201 #ifndef COMPASS_CAL_STICK_DELAY
202  #define COMPASS_CAL_STICK_DELAY 5.0f
203 #endif
204 
206 // OPTICAL_FLOW & VISUAL ODOMETRY
207 #ifndef OPTFLOW
208  # define OPTFLOW ENABLED
209 #endif
210 #ifndef VISUAL_ODOMETRY_ENABLED
211 # define VISUAL_ODOMETRY_ENABLED !HAL_MINIMIZE_FEATURES
212 #endif
213 
215 // Auto Tuning
216 #ifndef AUTOTUNE_ENABLED
217  # define AUTOTUNE_ENABLED ENABLED
218 #endif
219 
221 // Crop Sprayer - enabled only on larger firmwares
222 #ifndef SPRAYER
223  # define SPRAYER !HAL_MINIMIZE_FEATURES
224 #endif
225 
227 // Precision Landing with companion computer or IRLock sensor
228 #ifndef PRECISION_LANDING
229  # define PRECISION_LANDING ENABLED
230 #endif
231 
233 // gripper - enabled only on larger firmwares
234 #ifndef GRIPPER_ENABLED
235  # define GRIPPER_ENABLED !HAL_MINIMIZE_FEATURES
236 #endif
237 
239 // winch support - enabled only on larger firmwares
240 #ifndef WINCH_ENABLED
241 # define WINCH_ENABLED !HAL_MINIMIZE_FEATURES
242 #endif
243 
245 // rotations per minute sensor support
246 #ifndef RPM_ENABLED
247 # define RPM_ENABLED ENABLED
248 #endif
249 
251 // Parachute release
252 #ifndef PARACHUTE
253  # define PARACHUTE ENABLED
254 #endif
255 
257 // ADSB support
258 #ifndef ADSB_ENABLED
259 # define ADSB_ENABLED !HAL_MINIMIZE_FEATURES
260 #endif
261 
263 // Nav-Guided - allows external nav computer to control vehicle
264 #ifndef NAV_GUIDED
265  # define NAV_GUIDED !HAL_MINIMIZE_FEATURES
266 #endif
267 
269 // Acro - fly vehicle in acrobatic mode
270 #ifndef MODE_ACRO_ENABLED
271 # define MODE_ACRO_ENABLED ENABLED
272 #endif
273 
275 // Auto mode - allows vehicle to trace waypoints and perform automated actions
276 #ifndef MODE_AUTO_ENABLED
277 # define MODE_AUTO_ENABLED ENABLED
278 #endif
279 
281 // Brake mode - bring vehicle to stop
282 #ifndef MODE_BRAKE_ENABLED
283 # define MODE_BRAKE_ENABLED ENABLED
284 #endif
285 
287 // Circle - fly vehicle around a central point
288 #ifndef MODE_CIRCLE_ENABLED
289 # define MODE_CIRCLE_ENABLED ENABLED
290 #endif
291 
293 // Drift - fly vehicle in altitude-held, coordinated-turn mode
294 #ifndef MODE_DRIFT_ENABLED
295 # define MODE_DRIFT_ENABLED ENABLED
296 #endif
297 
299 // Follow - follow another vehicle or GCS
300 #ifndef MODE_FOLLOW_ENABLED
301 # define MODE_FOLLOW_ENABLED !HAL_MINIMIZE_FEATURES
302 #endif
303 
305 // Guided mode - control vehicle's position or angles from GCS
306 #ifndef MODE_GUIDED_ENABLED
307 # define MODE_GUIDED_ENABLED ENABLED
308 #endif
309 
311 // GuidedNoGPS mode - control vehicle's angles from GCS
312 #ifndef MODE_GUIDED_NOGPS_ENABLED
313 # define MODE_GUIDED_NOGPS_ENABLED ENABLED
314 #endif
315 
317 // Loiter mode - allows vehicle to hold global position
318 #ifndef MODE_LOITER_ENABLED
319 # define MODE_LOITER_ENABLED ENABLED
320 #endif
321 
323 // Position Hold - enable holding of global position
324 #ifndef MODE_POSHOLD_ENABLED
325 # define MODE_POSHOLD_ENABLED ENABLED
326 #endif
327 
329 // RTL - Return To Launch
330 #ifndef MODE_RTL_ENABLED
331 # define MODE_RTL_ENABLED ENABLED
332 #endif
333 
335 // SmartRTL - allows vehicle to retrace a (loop-eliminated) breadcrumb home
336 #ifndef MODE_SMARTRTL_ENABLED
337 # define MODE_SMARTRTL_ENABLED ENABLED
338 #endif
339 
341 // Sport - fly vehicle in rate-controlled (earth-frame) mode
342 #ifndef MODE_SPORT_ENABLED
343 # define MODE_SPORT_ENABLED !HAL_MINIMIZE_FEATURES
344 #endif
345 
347 // Throw - fly vehicle after throwing it in the air
348 #ifndef MODE_THROW_ENABLED
349 # define MODE_THROW_ENABLED ENABLED
350 #endif
351 
353 // Beacon support - support for local positioning systems
354 #ifndef BEACON_ENABLED
355 # define BEACON_ENABLED !HAL_MINIMIZE_FEATURES
356 #endif
357 
359 // RADIO CONFIGURATION
362 
363 
365 // FLIGHT_MODE
366 //
367 
368 #ifndef FLIGHT_MODE_1
369  # define FLIGHT_MODE_1 STABILIZE
370 #endif
371 #ifndef FLIGHT_MODE_2
372  # define FLIGHT_MODE_2 STABILIZE
373 #endif
374 #ifndef FLIGHT_MODE_3
375  # define FLIGHT_MODE_3 STABILIZE
376 #endif
377 #ifndef FLIGHT_MODE_4
378  # define FLIGHT_MODE_4 STABILIZE
379 #endif
380 #ifndef FLIGHT_MODE_5
381  # define FLIGHT_MODE_5 STABILIZE
382 #endif
383 #ifndef FLIGHT_MODE_6
384  # define FLIGHT_MODE_6 STABILIZE
385 #endif
386 
387 
389 // Throttle Failsafe
390 //
391 #ifndef FS_THR_VALUE_DEFAULT
392  # define FS_THR_VALUE_DEFAULT 975
393 #endif
394 
396 // Takeoff
397 //
398 #ifndef PILOT_TKOFF_ALT_DEFAULT
399  # define PILOT_TKOFF_ALT_DEFAULT 0 // default final alt above home for pilot initiated takeoff
400 #endif
401 
402 
404 // Landing
405 //
406 #ifndef LAND_SPEED
407  # define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s
408 #endif
409 #ifndef LAND_REPOSITION_DEFAULT
410  # define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing
411 #endif
412 #ifndef LAND_WITH_DELAY_MS
413  # define LAND_WITH_DELAY_MS 4000 // default delay (in milliseconds) when a land-with-delay is triggered during a failsafe event
414 #endif
415 #ifndef LAND_CANCEL_TRIGGER_THR
416  # define LAND_CANCEL_TRIGGER_THR 700 // land is cancelled by input throttle above 700
417 #endif
418 #ifndef LAND_RANGEFINDER_MIN_ALT_CM
419 #define LAND_RANGEFINDER_MIN_ALT_CM 200
420 #endif
421 
423 // Landing Detector
424 //
425 #ifndef LAND_DETECTOR_TRIGGER_SEC
426  # define LAND_DETECTOR_TRIGGER_SEC 1.0f // number of seconds to detect a landing
427 #endif
428 #ifndef LAND_DETECTOR_MAYBE_TRIGGER_SEC
429  # define LAND_DETECTOR_MAYBE_TRIGGER_SEC 0.2f // number of seconds that means we might be landed (used to reset horizontal position targets to prevent tipping over)
430 #endif
431 #ifndef LAND_DETECTOR_ACCEL_LPF_CUTOFF
432 # define LAND_DETECTOR_ACCEL_LPF_CUTOFF 1.0f // frequency cutoff of land detector accelerometer filter
433 #endif
434 #ifndef LAND_DETECTOR_ACCEL_MAX
435 # define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s
436 #endif
437 
439 // CAMERA TRIGGER AND CONTROL
440 //
441 #ifndef CAMERA
442  # define CAMERA ENABLED
443 #endif
444 
446 // MOUNT (ANTENNA OR CAMERA)
447 //
448 #ifndef MOUNT
449  # define MOUNT ENABLED
450 #endif
451 
452 
454 // Flight mode definitions
455 //
456 
457 // Acro Mode
458 #ifndef ACRO_RP_P
459  # define ACRO_RP_P 4.5f
460 #endif
461 
462 #ifndef ACRO_YAW_P
463  # define ACRO_YAW_P 4.5f
464 #endif
465 
466 #ifndef ACRO_LEVEL_MAX_ANGLE
467  # define ACRO_LEVEL_MAX_ANGLE 3000
468 #endif
469 
470 #ifndef ACRO_BALANCE_ROLL
471  #define ACRO_BALANCE_ROLL 1.0f
472 #endif
473 
474 #ifndef ACRO_BALANCE_PITCH
475  #define ACRO_BALANCE_PITCH 1.0f
476 #endif
477 
478 #ifndef ACRO_RP_EXPO_DEFAULT
479  #define ACRO_RP_EXPO_DEFAULT 0.3f
480 #endif
481 
482 #ifndef ACRO_Y_EXPO_DEFAULT
483  #define ACRO_Y_EXPO_DEFAULT 0.0f
484 #endif
485 
486 #ifndef ACRO_THR_MID_DEFAULT
487  #define ACRO_THR_MID_DEFAULT 0.0f
488 #endif
489 
490 // RTL Mode
491 #ifndef RTL_ALT_FINAL
492  # define RTL_ALT_FINAL 0 // the altitude the vehicle will move to as the final stage of Returning to Launch. Set to zero to land.
493 #endif
494 
495 #ifndef RTL_ALT
496  # define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude
497 #endif
498 
499 #ifndef RTL_ALT_MIN
500  # define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m)
501 #endif
502 
503 #ifndef RTL_CLIMB_MIN_DEFAULT
504  # define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL
505 #endif
506 
507 #ifndef RTL_ABS_MIN_CLIMB
508  # define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb
509 #endif
510 
511 #ifndef RTL_CONE_SLOPE_DEFAULT
512  # define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone
513 #endif
514 
515 #ifndef RTL_MIN_CONE_SLOPE
516  # define RTL_MIN_CONE_SLOPE 0.5f // minimum slope of cone
517 #endif
518 
519 #ifndef RTL_LOITER_TIME
520  # define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before beginning final descent
521 #endif
522 
523 // AUTO Mode
524 #ifndef WP_YAW_BEHAVIOR_DEFAULT
525  # define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL
526 #endif
527 
528 #ifndef AUTO_YAW_SLEW_RATE
529  # define AUTO_YAW_SLEW_RATE 60 // degrees/sec
530 #endif
531 
532 #ifndef YAW_LOOK_AHEAD_MIN_SPEED
533  # define YAW_LOOK_AHEAD_MIN_SPEED 100 // minimum ground speed in cm/s required before copter is aimed at ground course
534 #endif
535 
536 // Super Simple mode
537 #ifndef SUPER_SIMPLE_RADIUS
538  # define SUPER_SIMPLE_RADIUS 1000
539 #endif
540 
542 // Stabilize Rate Control
543 //
544 #ifndef ROLL_PITCH_YAW_INPUT_MAX
545  # define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range
546 #endif
547 #ifndef DEFAULT_ANGLE_MAX
548  # define DEFAULT_ANGLE_MAX 4500 // ANGLE_MAX parameters default value
549 #endif
550 #ifndef ANGLE_RATE_MAX
551  # define ANGLE_RATE_MAX 18000 // default maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
552 #endif
553 
555 // Stop mode defaults
556 //
557 #ifndef BRAKE_MODE_SPEED_Z
558  # define BRAKE_MODE_SPEED_Z 250 // z-axis speed in cm/s in Brake Mode
559 #endif
560 #ifndef BRAKE_MODE_DECEL_RATE
561  # define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode
562 #endif
563 
565 // PosHold parameter defaults
566 //
567 #ifndef POSHOLD_BRAKE_RATE_DEFAULT
568  # define POSHOLD_BRAKE_RATE_DEFAULT 8 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec
569 #endif
570 #ifndef POSHOLD_BRAKE_ANGLE_DEFAULT
571  # define POSHOLD_BRAKE_ANGLE_DEFAULT 3000 // default POSHOLD_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees
572 #endif
573 
575 // Throttle control defaults
576 //
577 
578 #ifndef THR_DZ_DEFAULT
579 # define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter
580 #endif
581 
582 // default maximum vertical velocity and acceleration the pilot may request
583 #ifndef PILOT_VELZ_MAX
584  # define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s
585 #endif
586 #ifndef PILOT_ACCEL_Z_DEFAULT
587  # define PILOT_ACCEL_Z_DEFAULT 250 // vertical acceleration in cm/s/s while altitude is under pilot control
588 #endif
589 
590 // max distance in cm above or below current location that will be used for the alt target when transitioning to alt-hold mode
591 #ifndef ALT_HOLD_INIT_MAX_OVERSHOOT
592  # define ALT_HOLD_INIT_MAX_OVERSHOOT 200
593 #endif
594 // the acceleration used to define the distance-velocity curve
595 #ifndef ALT_HOLD_ACCEL_MAX
596  # define ALT_HOLD_ACCEL_MAX 250 // if you change this you must also update the duplicate declaration in AC_WPNav.h
597 #endif
598 
599 #ifndef AUTO_DISARMING_DELAY
600 # define AUTO_DISARMING_DELAY 10
601 #endif
602 
604 // Throw mode configuration
605 //
606 #ifndef THROW_HIGH_SPEED
607 # define THROW_HIGH_SPEED 500.0f // vehicle much reach this total 3D speed in cm/s (or be free falling)
608 #endif
609 #ifndef THROW_VERTICAL_SPEED
610 # define THROW_VERTICAL_SPEED 50.0f // motors start when vehicle reaches this total 3D speed in cm/s
611 #endif
612 
614 // Dataflash logging control
615 //
616 #ifndef LOGGING_ENABLED
617  # define LOGGING_ENABLED ENABLED
618 #endif
619 
620 // Default logging bitmask
621 #ifndef DEFAULT_LOG_BITMASK
622  # define DEFAULT_LOG_BITMASK \
623  MASK_LOG_ATTITUDE_MED | \
624  MASK_LOG_GPS | \
625  MASK_LOG_PM | \
626  MASK_LOG_CTUN | \
627  MASK_LOG_NTUN | \
628  MASK_LOG_RCIN | \
629  MASK_LOG_IMU | \
630  MASK_LOG_CMD | \
631  MASK_LOG_CURRENT | \
632  MASK_LOG_RCOUT | \
633  MASK_LOG_OPTFLOW | \
634  MASK_LOG_COMPASS | \
635  MASK_LOG_CAMERA | \
636  MASK_LOG_MOTBATT
637 #endif
638 
640 // Fence, Rally and Terrain and AC_Avoidance defaults
641 //
642 
643 // Enable/disable Fence
644 #ifndef AC_FENCE
645  #define AC_FENCE ENABLED
646 #endif
647 
648 #ifndef AC_RALLY
649  #define AC_RALLY ENABLED
650 #endif
651 
652 #ifndef AC_TERRAIN
653  #define AC_TERRAIN ENABLED
654 #endif
655 
656 #if AC_TERRAIN && !AC_RALLY
657  #error Terrain relies on Rally which is disabled
658 #endif
659 
660 #ifndef AC_AVOID_ENABLED
661  #define AC_AVOID_ENABLED ENABLED
662 #endif
663 
664 #if AC_AVOID_ENABLED && !PROXIMITY_ENABLED
665  #error AC_Avoidance relies on PROXIMITY_ENABLED which is disabled
666 #endif
667 #if AC_AVOID_ENABLED && !AC_FENCE
668  #error AC_Avoidance relies on AC_FENCE which is disabled
669 #endif
670 
671 #if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED
672  #error Follow Mode relies on AC_AVOID which is disabled
673 #endif
674 
675 #if MODE_AUTO_ENABLED && !MODE_GUIDED_ENABLED
676  #error ModeAuto requires ModeGuided which is disabled
677 #endif
678 
679 #if MODE_AUTO_ENABLED && !MODE_CIRCLE_ENABLED
680  #error ModeAuto requires ModeCircle which is disabled
681 #endif
682 
683 #if MODE_AUTO_ENABLED && !MODE_RTL_ENABLED
684  #error ModeAuto requires ModeRTL which is disabled
685 #endif
686 
687 #if AC_TERRAIN && !MODE_AUTO_ENABLED
688  #error Terrain requires ModeAuto which is disabled
689 #endif
690 
691 #if FRAME_CONFIG == HELI_FRAME && !MODE_ACRO_ENABLED
692  #error Helicopter frame requires acro mode support which is disabled
693 #endif
694 
696 // Developer Items
697 //
698 
699 //use this to completely disable FRSKY TELEM
700 #ifndef FRSKY_TELEM_ENABLED
701  # define FRSKY_TELEM_ENABLED ENABLED
702 #endif
703 
704 #ifndef ADVANCED_FAILSAFE
705 # define ADVANCED_FAILSAFE DISABLED
706 #endif
707 
708 #ifndef CH_MODE_DEFAULT
709  # define CH_MODE_DEFAULT 5
710 #endif
711 
712 #ifndef TOY_MODE_ENABLED
713 #define TOY_MODE_ENABLED DISABLED
714 #endif
715 
716 #if TOY_MODE_ENABLED && FRAME_CONFIG == HELI_FRAME
717  #error Toy mode is not available on Helicopters
718 #endif
719 
720 #ifndef STATS_ENABLED
721  # define STATS_ENABLED ENABLED
722 #endif
723 
724 #ifndef DEVO_TELEM_ENABLED
725 #if HAL_MINIMIZE_FEATURES
726  #define DEVO_TELEM_ENABLED DISABLED
727 #else
728  #define DEVO_TELEM_ENABLED ENABLED
729 #endif
730 #endif