Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/config.h
Views: 1798
//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_CM96# define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters97#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 0214#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_SPEED321# define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/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_CM333#define LAND_RANGEFINDER_MIN_ALT_CM 200334#endif335336//////////////////////////////////////////////////////////////////////////////337// Landing Detector338//339#ifndef LAND_DETECTOR_TRIGGER_SEC340# define LAND_DETECTOR_TRIGGER_SEC 1.0f // number of seconds to detect a landing341#endif342#ifndef LAND_AIRMODE_DETECTOR_TRIGGER_SEC343# define LAND_AIRMODE_DETECTOR_TRIGGER_SEC 3.0f // number of seconds to detect a landing in air mode344#endif345#ifndef LAND_DETECTOR_MAYBE_TRIGGER_SEC346# 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)347#endif348#ifndef LAND_DETECTOR_ACCEL_LPF_CUTOFF349# define LAND_DETECTOR_ACCEL_LPF_CUTOFF 1.0f // frequency cutoff of land detector accelerometer filter350#endif351#ifndef LAND_DETECTOR_ACCEL_MAX352# define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s353#endif354#ifndef LAND_DETECTOR_VEL_Z_MAX355# define LAND_DETECTOR_VEL_Z_MAX 1.0f // vehicle vertical velocity must be under 1m/s356#endif357358//////////////////////////////////////////////////////////////////////////////359// Flight mode definitions360//361362// Acro Mode363#ifndef ACRO_LEVEL_MAX_ANGLE364# define ACRO_LEVEL_MAX_ANGLE 3000 // maximum lean angle in trainer mode measured in centidegrees365#endif366367#ifndef ACRO_LEVEL_MAX_OVERSHOOT368# define ACRO_LEVEL_MAX_OVERSHOOT 1000 // maximum overshoot angle in trainer mode when full roll or pitch stick is held in centidegrees369#endif370371#ifndef ACRO_BALANCE_ROLL372#define ACRO_BALANCE_ROLL 1.0f373#endif374375#ifndef ACRO_BALANCE_PITCH376#define ACRO_BALANCE_PITCH 1.0f377#endif378379#ifndef ACRO_RP_EXPO_DEFAULT380#define ACRO_RP_EXPO_DEFAULT 0.3f // ACRO roll and pitch expo parameter default381#endif382383#ifndef ACRO_Y_EXPO_DEFAULT384#define ACRO_Y_EXPO_DEFAULT 0.0f // ACRO yaw expo parameter default385#endif386387#ifndef ACRO_THR_MID_DEFAULT388#define ACRO_THR_MID_DEFAULT 0.0f389#endif390391#ifndef ACRO_RP_RATE_DEFAULT392#define ACRO_RP_RATE_DEFAULT 360 // ACRO roll and pitch rotation rate parameter default in deg/s393#endif394395#ifndef ACRO_Y_RATE_DEFAULT396#define ACRO_Y_RATE_DEFAULT 202.5 // ACRO yaw rotation rate parameter default in deg/s397#endif398399// RTL Mode400#ifndef RTL_ALT_FINAL401# define RTL_ALT_FINAL 0 // the altitude, in cm, the vehicle will move to as the final stage of Returning to Launch. Set to zero to land.402#endif403404#ifndef RTL_ALT405# define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude406#endif407408#ifndef RTL_ALT_MIN409# define RTL_ALT_MIN 30 // min height above ground for RTL (i.e 30cm)410#endif411412#ifndef RTL_CLIMB_MIN_DEFAULT413# define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL414#endif415416#ifndef RTL_CONE_SLOPE_DEFAULT417# define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone418#endif419420#ifndef RTL_MIN_CONE_SLOPE421# define RTL_MIN_CONE_SLOPE 0.5f // minimum slope of cone422#endif423424#ifndef RTL_LOITER_TIME425# define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before beginning final descent426#endif427428// AUTO Mode429#ifndef WP_YAW_BEHAVIOR_DEFAULT430# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL431#endif432433#ifndef YAW_LOOK_AHEAD_MIN_SPEED434# define YAW_LOOK_AHEAD_MIN_SPEED 100 // minimum ground speed in cm/s required before copter is aimed at ground course435#endif436437// Super Simple mode438#ifndef SUPER_SIMPLE_RADIUS439# define SUPER_SIMPLE_RADIUS 1000440#endif441442//////////////////////////////////////////////////////////////////////////////443// Stabilize Rate Control444//445#ifndef ROLL_PITCH_YAW_INPUT_MAX446# define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range447#endif448#ifndef DEFAULT_ANGLE_MAX449# define DEFAULT_ANGLE_MAX 3000 // ANGLE_MAX parameters default value450#endif451452//////////////////////////////////////////////////////////////////////////////453// Stop mode defaults454//455#ifndef BRAKE_MODE_SPEED_Z456# define BRAKE_MODE_SPEED_Z 250 // z-axis speed in cm/s in Brake Mode457#endif458#ifndef BRAKE_MODE_DECEL_RATE459# define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode460#endif461462//////////////////////////////////////////////////////////////////////////////463// PosHold parameter defaults464//465#ifndef POSHOLD_BRAKE_RATE_DEFAULT466# define POSHOLD_BRAKE_RATE_DEFAULT 8 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec467#endif468#ifndef POSHOLD_BRAKE_ANGLE_DEFAULT469# define POSHOLD_BRAKE_ANGLE_DEFAULT 3000 // default POSHOLD_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees470#endif471472//////////////////////////////////////////////////////////////////////////////473// Pilot control defaults474//475476#ifndef THR_DZ_DEFAULT477# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter478#endif479480// default maximum vertical velocity and acceleration the pilot may request481#ifndef PILOT_VELZ_MAX482# define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s483#endif484#ifndef PILOT_ACCEL_Z_DEFAULT485# define PILOT_ACCEL_Z_DEFAULT 250 // vertical acceleration in cm/s/s while altitude is under pilot control486#endif487488#ifndef PILOT_Y_RATE_DEFAULT489# define PILOT_Y_RATE_DEFAULT 202.5 // yaw rotation rate parameter default in deg/s for all mode except ACRO490#endif491#ifndef PILOT_Y_EXPO_DEFAULT492# define PILOT_Y_EXPO_DEFAULT 0.0 // yaw expo parameter default for all mode except ACRO493#endif494495#ifndef AUTO_DISARMING_DELAY496# define AUTO_DISARMING_DELAY 10497#endif498499//////////////////////////////////////////////////////////////////////////////500// Throw mode configuration501//502#ifndef THROW_HIGH_SPEED503# define THROW_HIGH_SPEED 500.0f // vehicle much reach this total 3D speed in cm/s (or be free falling)504#endif505#ifndef THROW_VERTICAL_SPEED506# define THROW_VERTICAL_SPEED 50.0f // motors start when vehicle reaches this total 3D speed in cm/s507#endif508509//////////////////////////////////////////////////////////////////////////////510// Logging control511//512513// Default logging bitmask514#ifndef DEFAULT_LOG_BITMASK515# define DEFAULT_LOG_BITMASK \516MASK_LOG_ATTITUDE_MED | \517MASK_LOG_GPS | \518MASK_LOG_PM | \519MASK_LOG_CTUN | \520MASK_LOG_NTUN | \521MASK_LOG_RCIN | \522MASK_LOG_IMU | \523MASK_LOG_CMD | \524MASK_LOG_CURRENT | \525MASK_LOG_RCOUT | \526MASK_LOG_OPTFLOW | \527MASK_LOG_COMPASS | \528MASK_LOG_CAMERA | \529MASK_LOG_MOTBATT530#endif531532//////////////////////////////////////////////////////////////////////////////533// Fence, Rally and Terrain and AC_Avoidance defaults534//535536#if MODE_FOLLOW_ENABLED && !AP_AVOIDANCE_ENABLED537#error Follow Mode relies on AP_AVOIDANCE_ENABLED which is disabled538#endif539540#if MODE_AUTO_ENABLED && !MODE_GUIDED_ENABLED541#error ModeAuto requires ModeGuided which is disabled542#endif543544#if MODE_AUTO_ENABLED && !MODE_CIRCLE_ENABLED545#error ModeAuto requires ModeCircle which is disabled546#endif547548#if MODE_AUTO_ENABLED && !MODE_RTL_ENABLED549#error ModeAuto requires ModeRTL which is disabled550#endif551552#if FRAME_CONFIG == HELI_FRAME && !MODE_ACRO_ENABLED553#error Helicopter frame requires acro mode support which is disabled554#endif555556#if MODE_SMARTRTL_ENABLED && !MODE_RTL_ENABLED557#error SmartRTL requires ModeRTL which is disabled558#endif559560#if HAL_ADSB_ENABLED && !MODE_GUIDED_ENABLED561#error ADSB requires ModeGuided which is disabled562#endif563564#if MODE_FOLLOW_ENABLED && !MODE_GUIDED_ENABLED565#error Follow requires ModeGuided which is disabled566#endif567568#if MODE_GUIDED_NOGPS_ENABLED && !MODE_GUIDED_ENABLED569#error ModeGuided-NoGPS requires ModeGuided which is disabled570#endif571572//////////////////////////////////////////////////////////////////////////////573// Developer Items574//575576#ifndef AP_COPTER_ADVANCED_FAILSAFE_ENABLED577# define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 0578#endif579580#ifndef CH_MODE_DEFAULT581# define CH_MODE_DEFAULT 5582#endif583584#ifndef TOY_MODE_ENABLED585#define TOY_MODE_ENABLED 0586#endif587588#if TOY_MODE_ENABLED && FRAME_CONFIG == HELI_FRAME589#error Toy mode is not available on Helicopters590#endif591592#ifndef HAL_FRAME_TYPE_DEFAULT593#define HAL_FRAME_TYPE_DEFAULT AP_Motors::MOTOR_FRAME_TYPE_X594#endif595596#ifndef AC_CUSTOMCONTROL_MULTI_ENABLED597#define AC_CUSTOMCONTROL_MULTI_ENABLED FRAME_CONFIG == MULTICOPTER_FRAME && AP_CUSTOMCONTROL_ENABLED598#endif599600#ifndef AC_PAYLOAD_PLACE_ENABLED601#define AC_PAYLOAD_PLACE_ENABLED 1602#endif603604#ifndef USER_PARAMS_ENABLED605#define USER_PARAMS_ENABLED 0606#endif607608609