//1#pragma once23//////////////////////////////////////////////////////////////////////////////4//////////////////////////////////////////////////////////////////////////////5//6// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING7//8// DO NOT EDIT this file to adjust your configuration. Create your own9// APM_Config.h and use APM_Config.h.example as a reference.10//11// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING12///13//////////////////////////////////////////////////////////////////////////////14//////////////////////////////////////////////////////////////////////////////15//16// Default and automatic configuration details.17//18// Notes for maintainers:19//20// - Try to keep this file organised in the same order as APM_Config.h.example21//22#include "defines.h"2324///25/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that26/// change in your local copy of APM_Config.h.27///28#include "APM_Config.h"29#include <AP_ADSB/AP_ADSB_config.h>30#include <AP_Follow/AP_Follow_config.h>31#include <AC_Avoidance/AC_Avoidance_config.h>3233//////////////////////////////////////////////////////////////////////////////34//////////////////////////////////////////////////////////////////////////////35// HARDWARE CONFIGURATION AND CONNECTIONS36//////////////////////////////////////////////////////////////////////////////37//////////////////////////////////////////////////////////////////////////////3839#ifndef CONFIG_HAL_BOARD40#error CONFIG_HAL_BOARD must be defined to build ArduCopter41#endif4243#ifndef ARMING_DELAY_SEC44# define ARMING_DELAY_SEC 2.0f45#endif4647//////////////////////////////////////////////////////////////////////////////48// FRAME_CONFIG49//50#ifndef FRAME_CONFIG51# define FRAME_CONFIG MULTICOPTER_FRAME52#endif5354/////////////////////////////////////////////////////////////////////////////////55// TradHeli defaults56#if FRAME_CONFIG == HELI_FRAME57# define RC_FAST_SPEED 12558# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD59#endif6061//////////////////////////////////////////////////////////////////////////////62// PWM control63// default RC speed in Hz64#ifndef RC_FAST_SPEED65# define RC_FAST_SPEED 49066#endif6768//////////////////////////////////////////////////////////////////////////////69// Rangefinder70//7172#ifndef RANGEFINDER_FILT_DEFAULT73# define RANGEFINDER_FILT_DEFAULT 0.5f // filter for rangefinder distance74#endif7576#ifndef SURFACE_TRACKING_TIMEOUT_MS77# define SURFACE_TRACKING_TIMEOUT_MS 1000 // surface tracking target alt will reset to current rangefinder alt after this many milliseconds without a good rangefinder alt78#endif7980#ifndef MAV_SYSTEM_ID81# define MAV_SYSTEM_ID 182#endif8384// prearm GPS hdop check85#ifndef GPS_HDOP_GOOD_DEFAULT86# define GPS_HDOP_GOOD_DEFAULT 140 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled87#endif8889// missing terrain data failsafe90#ifndef FS_TERRAIN_TIMEOUT_MS91#define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL)92#endif9394// pre-arm baro vs inertial nav max alt disparity95#ifndef PREARM_MAX_ALT_DISPARITY_M96# define PREARM_MAX_ALT_DISPARITY_M 1.0 // barometer and inertial nav altitude must be within this many meters97#endif9899//////////////////////////////////////////////////////////////////////////////100// EKF Failsafe101#ifndef FS_EKF_ACTION_DEFAULT102# define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_LAND // EKF failsafe triggers land by default103#endif104#ifndef FS_EKF_THRESHOLD_DEFAULT105# define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered106#endif107108#ifndef EKF_ORIGIN_MAX_ALT_KM109# define EKF_ORIGIN_MAX_ALT_KM 50 // EKF origin and home must be within 50km vertically110#endif111112#ifndef FS_EKF_FILT_DEFAULT113# define FS_EKF_FILT_DEFAULT 5.0f // frequency cutoff of EKF variance filters114#endif115116//////////////////////////////////////////////////////////////////////////////117// Auto Tuning118#ifndef AUTOTUNE_ENABLED119# define AUTOTUNE_ENABLED 1120#endif121122//////////////////////////////////////////////////////////////////////////////123// Nav-Guided - allows external nav computer to control vehicle124#ifndef AC_NAV_GUIDED125# define AC_NAV_GUIDED 1126#endif127128//////////////////////////////////////////////////////////////////////////////129// Acro - fly vehicle in acrobatic mode130#ifndef MODE_ACRO_ENABLED131# define MODE_ACRO_ENABLED 1132#endif133134//////////////////////////////////////////////////////////////////////////////135// Auto mode - allows vehicle to trace waypoints and perform automated actions136#ifndef MODE_AUTO_ENABLED137# define MODE_AUTO_ENABLED 1138#endif139140//////////////////////////////////////////////////////////////////////////////141// Brake mode - bring vehicle to stop142#ifndef MODE_BRAKE_ENABLED143# define MODE_BRAKE_ENABLED 1144#endif145146//////////////////////////////////////////////////////////////////////////////147// Circle - fly vehicle around a central point148#ifndef MODE_CIRCLE_ENABLED149# define MODE_CIRCLE_ENABLED 1150#endif151152//////////////////////////////////////////////////////////////////////////////153// Drift - fly vehicle in altitude-held, coordinated-turn mode154#ifndef MODE_DRIFT_ENABLED155# define MODE_DRIFT_ENABLED 1156#endif157158//////////////////////////////////////////////////////////////////////////////159// flip - fly vehicle in flip in pitch and roll direction mode160#ifndef MODE_FLIP_ENABLED161# define MODE_FLIP_ENABLED 1162#endif163164//////////////////////////////////////////////////////////////////////////////165// Follow - follow another vehicle or GCS166#ifndef MODE_FOLLOW_ENABLED167#if AP_FOLLOW_ENABLED && AP_AVOIDANCE_ENABLED168#define MODE_FOLLOW_ENABLED 1169#else170#define MODE_FOLLOW_ENABLED 0171#endif172#endif173174//////////////////////////////////////////////////////////////////////////////175// Guided mode - control vehicle's position or angles from GCS176#ifndef MODE_GUIDED_ENABLED177# define MODE_GUIDED_ENABLED 1178#endif179180//////////////////////////////////////////////////////////////////////////////181// GuidedNoGPS mode - control vehicle's angles from GCS182#ifndef MODE_GUIDED_NOGPS_ENABLED183# define MODE_GUIDED_NOGPS_ENABLED 1184#endif185186//////////////////////////////////////////////////////////////////////////////187// Loiter mode - allows vehicle to hold global position188#ifndef MODE_LOITER_ENABLED189# define MODE_LOITER_ENABLED 1190#endif191192//////////////////////////////////////////////////////////////////////////////193// Position Hold - enable holding of global position194#ifndef MODE_POSHOLD_ENABLED195# define MODE_POSHOLD_ENABLED 1196#endif197198//////////////////////////////////////////////////////////////////////////////199// RTL - Return To Launch200#ifndef MODE_RTL_ENABLED201# define MODE_RTL_ENABLED 1202#endif203204//////////////////////////////////////////////////////////////////////////////205// SmartRTL - allows vehicle to retrace a (loop-eliminated) breadcrumb home206#ifndef MODE_SMARTRTL_ENABLED207# define MODE_SMARTRTL_ENABLED 1208#endif209210//////////////////////////////////////////////////////////////////////////////211// Sport - fly vehicle in rate-controlled (earth-frame) mode212#ifndef MODE_SPORT_ENABLED213# define MODE_SPORT_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)214#endif215216//////////////////////////////////////////////////////////////////////////////217// System ID - conduct system identification tests on vehicle218#ifndef MODE_SYSTEMID_ENABLED219# define MODE_SYSTEMID_ENABLED HAL_LOGGING_ENABLED220#endif221222//////////////////////////////////////////////////////////////////////////////223// Throw - fly vehicle after throwing it in the air224#ifndef MODE_THROW_ENABLED225# define MODE_THROW_ENABLED 1226#endif227228//////////////////////////////////////////////////////////////////////////////229// ZigZag - allow vehicle to fly in a zigzag manner with predefined point A B230#ifndef MODE_ZIGZAG_ENABLED231# define MODE_ZIGZAG_ENABLED 1232#endif233234//////////////////////////////////////////////////////////////////////////////235// Turtle - allow vehicle to be flipped over after a crash236#ifndef MODE_TURTLE_ENABLED237# define MODE_TURTLE_ENABLED HAL_DSHOT_ENABLED && FRAME_CONFIG != HELI_FRAME238#endif239240//////////////////////////////////////////////////////////////////////////////241// Flowhold - use optical flow to hover in place242#ifndef MODE_FLOWHOLD_ENABLED243# define MODE_FLOWHOLD_ENABLED AP_OPTICALFLOW_ENABLED244#endif245246//////////////////////////////////////////////////////////////////////////////247248//////////////////////////////////////////////////////////////////////////////249// Weathervane - allow vehicle to yaw into wind250#ifndef WEATHERVANE_ENABLED251# define WEATHERVANE_ENABLED 1252#endif253254//////////////////////////////////////////////////////////////////////////////255256//////////////////////////////////////////////////////////////////////////////257// Autorotate - autonomous auto-rotation - helicopters only258#ifndef MODE_AUTOROTATE_ENABLED259#if CONFIG_HAL_BOARD == HAL_BOARD_SITL260#if FRAME_CONFIG == HELI_FRAME261#ifndef MODE_AUTOROTATE_ENABLED262# define MODE_AUTOROTATE_ENABLED 1263#endif264#else265# define MODE_AUTOROTATE_ENABLED 0266#endif267#else268# define MODE_AUTOROTATE_ENABLED 0269#endif270#endif271272//////////////////////////////////////////////////////////////////////////////273// RADIO CONFIGURATION274//////////////////////////////////////////////////////////////////////////////275//////////////////////////////////////////////////////////////////////////////276277278//////////////////////////////////////////////////////////////////////////////279// FLIGHT_MODE280//281282#ifndef FLIGHT_MODE_1283# define FLIGHT_MODE_1 Mode::Number::STABILIZE284#endif285#ifndef FLIGHT_MODE_2286# define FLIGHT_MODE_2 Mode::Number::STABILIZE287#endif288#ifndef FLIGHT_MODE_3289# define FLIGHT_MODE_3 Mode::Number::STABILIZE290#endif291#ifndef FLIGHT_MODE_4292# define FLIGHT_MODE_4 Mode::Number::STABILIZE293#endif294#ifndef FLIGHT_MODE_5295# define FLIGHT_MODE_5 Mode::Number::STABILIZE296#endif297#ifndef FLIGHT_MODE_6298# define FLIGHT_MODE_6 Mode::Number::STABILIZE299#endif300301302//////////////////////////////////////////////////////////////////////////////303// Throttle Failsafe304//305#ifndef FS_THR_VALUE_DEFAULT306# define FS_THR_VALUE_DEFAULT 975307#endif308309//////////////////////////////////////////////////////////////////////////////310// Takeoff311//312#ifndef PILOT_TKOFF_ALT_DEFAULT313# define PILOT_TKOFF_ALT_DEFAULT 0 // default final alt above home for pilot initiated takeoff314#endif315316317//////////////////////////////////////////////////////////////////////////////318// Landing319//320#ifndef LAND_SPD_MS_DEFAULT321# define LAND_SPD_MS_DEFAULT 0.5f // the descent speed for the final stage of landing in m/s322#endif323#ifndef LAND_REPOSITION_DEFAULT324# define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing325#endif326#ifndef LAND_WITH_DELAY_MS327# define LAND_WITH_DELAY_MS 4000 // default delay (in milliseconds) when a land-with-delay is triggered during a failsafe event328#endif329#ifndef LAND_CANCEL_TRIGGER_THR330# define LAND_CANCEL_TRIGGER_THR 700 // land is cancelled by input throttle above 700331#endif332#ifndef LAND_RANGEFINDER_MIN_ALT_M333#define LAND_RANGEFINDER_MIN_ALT_M 2.0334#endif335336// error if old LAND parameter default definitions are used337#ifdef LAND_SPEED338#error "LAND_SPEED definition replaced with LAND_SPD_MS_DEFAULT"339#endif340341//////////////////////////////////////////////////////////////////////////////342// Landing Detector343//344#ifndef LAND_DETECTOR_TRIGGER_SEC345# define LAND_DETECTOR_TRIGGER_SEC 1.0f // number of seconds to detect a landing346#endif347#ifndef LAND_AIRMODE_DETECTOR_TRIGGER_SEC348# define LAND_AIRMODE_DETECTOR_TRIGGER_SEC 3.0f // number of seconds to detect a landing in air mode349#endif350#ifndef LAND_DETECTOR_MAYBE_TRIGGER_SEC351# 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)352#endif353#ifndef LAND_DETECTOR_ACCEL_LPF_CUTOFF354# define LAND_DETECTOR_ACCEL_LPF_CUTOFF 1.0f // frequency cutoff of land detector accelerometer filter355#endif356#ifndef LAND_DETECTOR_ACCEL_MAX357# define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s358#endif359#ifndef LAND_DETECTOR_VEL_Z_MAX360# define LAND_DETECTOR_VEL_Z_MAX 1.0f // vehicle vertical velocity must be under 1m/s361#endif362363//////////////////////////////////////////////////////////////////////////////364// Flight mode definitions365//366367// Acro Mode368#ifndef ACRO_LEVEL_MAX_ANGLE_RAD369# define ACRO_LEVEL_MAX_ANGLE_RAD radians(30.0) // maximum lean angle in trainer mode measured in radians370#endif371372#ifdef ACRO_LEVEL_MAX_ANGLE373#error "Please update your hwdef to use ACRO_LEVEL_MAX_ANGLE_RAD, not ACRO_LEVEL_MAX_ANGLE"374#endif // ACRO_LEVEL_MAX_ANGLE375376#ifndef ACRO_LEVEL_MAX_OVERSHOOT_RAD377# define ACRO_LEVEL_MAX_OVERSHOOT_RAD radians(10.0) // maximum overshoot angle in trainer mode when full roll or pitch stick is held in radians378#endif379380#ifdef ACRO_LEVEL_MAX_OVERSHOOT381#error "Please update your hwdef to use ACRO_LEVEL_MAX_OVERSHOOT_RAD, not ACRO_LEVEL_MAX_OVERSHOOT"382#endif // ACRO_LEVEL_MAX_OVERSHOOT383384#ifndef ACRO_BALANCE_ROLL385#define ACRO_BALANCE_ROLL 1.0f386#endif387388#ifndef ACRO_BALANCE_PITCH389#define ACRO_BALANCE_PITCH 1.0f390#endif391392#ifndef ACRO_RP_EXPO_DEFAULT393#define ACRO_RP_EXPO_DEFAULT 0.3f // ACRO roll and pitch expo parameter default394#endif395396#ifndef ACRO_Y_EXPO_DEFAULT397#define ACRO_Y_EXPO_DEFAULT 0.0f // ACRO yaw expo parameter default398#endif399400#ifndef ACRO_THR_MID_DEFAULT401#define ACRO_THR_MID_DEFAULT 0.0f402#endif403404#ifndef ACRO_RP_RATE_DEFAULT405#define ACRO_RP_RATE_DEFAULT 360 // ACRO roll and pitch rotation rate parameter default in deg/s406#endif407408#ifndef ACRO_Y_RATE_DEFAULT409#define ACRO_Y_RATE_DEFAULT 202.5 // ACRO yaw rotation rate parameter default in deg/s410#endif411412// RTL Mode413#ifndef RTL_ALT_FINAL_M_DEFAULT414# define RTL_ALT_FINAL_M_DEFAULT 0 // the altitude, in meters, the vehicle will move to as the final stage of Returning to Launch. Set to zero to land.415#endif416417#ifndef RTL_ALT_M_DEFAULT418# define RTL_ALT_M_DEFAULT 15 // default alt to return to home in meters, 0 = Maintain current altitude419#endif420421#ifndef RTL_ALT_MIN_M422# define RTL_ALT_MIN_M 0.30 // min height above ground for RTL (i.e 0.3 m)423#endif424425#ifndef RTL_CLIMB_MIN_M_DEFAULT426# define RTL_CLIMB_MIN_M_DEFAULT 0 // vehicle will always climb this many meters during the first stage of RTL427#endif428429#ifndef RTL_CONE_SLOPE_DEFAULT430# define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone431#endif432433#ifndef RTL_MIN_CONE_SLOPE434# define RTL_MIN_CONE_SLOPE 0.5f // minimum slope of cone435#endif436437#ifndef RTL_LOITER_TIME438# define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before beginning final descent439#endif440441// error if old RTL parameter default definitions are used442#ifdef RTL_ALT_FINAL443#error "RTL_ALT_FINAL definition replaced with RTL_ALT_FINAL_M_DEFAULT"444#endif445#ifdef RTL_ALT446#error "RTL_ALT definition replaced with RTL_ALT_M_DEFAULT"447#endif448#ifdef RTL_CLIMB_MIN_DEFAULT449#error "RTL_CLIMB_MIN_DEFAULT definition replaced with RTL_CLIMB_MIN_M_DEFAULT"450#endif451452// AUTO Mode453#ifndef WP_YAW_BEHAVIOR_DEFAULT454# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL455#endif456457#ifndef YAW_LOOK_AHEAD_MIN_SPEED_MS458# define YAW_LOOK_AHEAD_MIN_SPEED_MS 1 // minimum ground speed in m/s required before copter is aimed at ground course459#endif460461// Super Simple mode462#ifndef SUPER_SIMPLE_RADIUS_M463# define SUPER_SIMPLE_RADIUS_M 10.0464#endif465466//////////////////////////////////////////////////////////////////////////////467// Stabilize Rate Control468//469#ifndef ROLL_PITCH_YAW_INPUT_MAX470# define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range471#endif472473#ifdef DEFAULT_ANGLE_MAX474#error "DEFAULT_ANGLE_MAX definition replaced with AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT (in degrees)"475#endif476477//////////////////////////////////////////////////////////////////////////////478// Stop mode defaults479//480#ifndef BRAKE_MODE_SPEED_Z_MS481# define BRAKE_MODE_SPEED_Z_MS 2.50 // z-axis speed in m/s in Brake Mode482#endif483#ifndef BRAKE_MODE_DECEL_RATE_MSS484# define BRAKE_MODE_DECEL_RATE_MSS 7.50 // acceleration rate in m/s/s in Brake Mode485#endif486487//////////////////////////////////////////////////////////////////////////////488// PosHold parameter defaults489//490#ifndef POSHOLD_BRAKE_RATE_DEFAULT491#if FRAME_CONFIG == HELI_FRAME492# define POSHOLD_BRAKE_RATE_DEFAULT 4 // default POSHOLD_BRAKE_RATE param value for tradheli. Rotation rate during braking in deg/sec493# define POSHOLD_BRAKE_RATE_MIN 4 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec494#else495# define POSHOLD_BRAKE_RATE_DEFAULT 8 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec496# define POSHOLD_BRAKE_RATE_MIN 4 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec497#endif498#endif499#ifndef POSHOLD_BRAKE_ANGLE_DEFAULT500#if FRAME_CONFIG == HELI_FRAME501# define POSHOLD_BRAKE_ANGLE_DEFAULT 800 // default POSHOLD_BRAKE_ANGLE param value for tradheli. Max lean angle during braking in centi-degrees502#else503# define POSHOLD_BRAKE_ANGLE_DEFAULT 3000 // default POSHOLD_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees504#endif505#endif506507//////////////////////////////////////////////////////////////////////////////508// Pilot control defaults509//510511#ifndef THR_DZ_DEFAULT512# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter513#endif514515// default maximum vertical velocity and acceleration the pilot may request516#ifndef PILOT_SPEED_UP_DEFAULT517# define PILOT_SPEED_UP_DEFAULT 250 // maximum vertical velocity in cm/s518#endif519#ifndef PILOT_ACCEL_Z_DEFAULT520# define PILOT_ACCEL_Z_DEFAULT 250 // vertical acceleration in cm/s/s while altitude is under pilot control521#endif522523#ifndef PILOT_Y_RATE_DEFAULT524# define PILOT_Y_RATE_DEFAULT 202.5 // yaw rotation rate parameter default in deg/s for all mode except ACRO525#endif526#ifndef PILOT_Y_EXPO_DEFAULT527# define PILOT_Y_EXPO_DEFAULT 0.0 // yaw expo parameter default for all mode except ACRO528#endif529530#ifndef AUTO_DISARMING_DELAY531# define AUTO_DISARMING_DELAY 10532#endif533534//////////////////////////////////////////////////////////////////////////////535// Throw mode configuration536//537#ifndef THROW_HIGH_SPEED_MS538# define THROW_HIGH_SPEED_MS 5.0 // vehicle much reach this total 3D speed in cm/s (or be free falling)539#endif540#ifndef THROW_VERTICAL_SPEED_MS541# define THROW_VERTICAL_SPEED_MS 0.5 // motors start when vehicle reaches this total 3D speed in cm/s542#endif543544//////////////////////////////////////////////////////////////////////////////545// Logging control546//547548// Default logging bitmask549#ifndef DEFAULT_LOG_BITMASK550# define DEFAULT_LOG_BITMASK \551MASK_LOG_ATTITUDE_MED | \552MASK_LOG_GPS | \553MASK_LOG_PM | \554MASK_LOG_CTUN | \555MASK_LOG_NTUN | \556MASK_LOG_RCIN | \557MASK_LOG_IMU | \558MASK_LOG_CMD | \559MASK_LOG_CURRENT | \560MASK_LOG_RCOUT | \561MASK_LOG_OPTFLOW | \562MASK_LOG_PID | \563MASK_LOG_COMPASS | \564MASK_LOG_CAMERA | \565MASK_LOG_MOTBATT566#endif567568//////////////////////////////////////////////////////////////////////////////569// Fence, Rally and Terrain and AC_Avoidance defaults570//571572#if MODE_FOLLOW_ENABLED && !AP_AVOIDANCE_ENABLED573#error Follow Mode relies on AP_AVOIDANCE_ENABLED which is disabled574#endif575576#if MODE_AUTO_ENABLED && !MODE_GUIDED_ENABLED577#error ModeAuto requires ModeGuided which is disabled578#endif579580#if MODE_AUTO_ENABLED && !MODE_CIRCLE_ENABLED581#error ModeAuto requires ModeCircle which is disabled582#endif583584#if MODE_AUTO_ENABLED && !MODE_RTL_ENABLED585#error ModeAuto requires ModeRTL which is disabled586#endif587588#if FRAME_CONFIG == HELI_FRAME && !MODE_ACRO_ENABLED589#error Helicopter frame requires acro mode support which is disabled590#endif591592#if MODE_SMARTRTL_ENABLED && !MODE_RTL_ENABLED593#error SmartRTL requires ModeRTL which is disabled594#endif595596#if HAL_ADSB_ENABLED && !MODE_GUIDED_ENABLED597#error ADSB requires ModeGuided which is disabled598#endif599600#if MODE_FOLLOW_ENABLED && !MODE_GUIDED_ENABLED601#error Follow requires ModeGuided which is disabled602#endif603604#if MODE_GUIDED_NOGPS_ENABLED && !MODE_GUIDED_ENABLED605#error ModeGuided-NoGPS requires ModeGuided which is disabled606#endif607608//////////////////////////////////////////////////////////////////////////////609// Developer Items610//611612#ifndef AP_COPTER_ADVANCED_FAILSAFE_ENABLED613# define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 0614#endif615616#ifndef AP_COPTER_AHRS_AUTO_TRIM_ENABLED617# define AP_COPTER_AHRS_AUTO_TRIM_ENABLED 1618#endif619620#ifndef CH_MODE_DEFAULT621# define CH_MODE_DEFAULT 5622#endif623624#ifndef TOY_MODE_ENABLED625#define TOY_MODE_ENABLED 0626#endif627628#if TOY_MODE_ENABLED && FRAME_CONFIG == HELI_FRAME629#error Toy mode is not available on Helicopters630#endif631632#ifndef HAL_FRAME_TYPE_DEFAULT633#define HAL_FRAME_TYPE_DEFAULT AP_Motors::MOTOR_FRAME_TYPE_X634#endif635636#ifndef AC_CUSTOMCONTROL_MULTI_ENABLED637#define AC_CUSTOMCONTROL_MULTI_ENABLED FRAME_CONFIG == MULTICOPTER_FRAME && AP_CUSTOMCONTROL_ENABLED638#endif639640#ifndef AC_PAYLOAD_PLACE_ENABLED641#define AC_PAYLOAD_PLACE_ENABLED 1642#endif643644#ifndef USER_PARAMS_ENABLED645#define USER_PARAMS_ENABLED 0646#endif647648649