Go to the documentation of this file. 38 #ifndef CONFIG_HAL_BOARD 39 #error CONFIG_HAL_BOARD must be defined to build ArduCopter 46 #define HIL_MODE HIL_MODE_DISABLED 49 #define MAGNETOMETER ENABLED 51 #ifndef ARMING_DELAY_SEC 52 # define ARMING_DELAY_SEC 2.0f 59 # define FRAME_CONFIG MULTICOPTER_FRAME 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 76 # define RC_FAST_SPEED 490 83 #ifndef RANGEFINDER_ENABLED 84 # define RANGEFINDER_ENABLED ENABLED 87 #ifndef RANGEFINDER_HEALTH_MAX 88 # define RANGEFINDER_HEALTH_MAX 3 // number of good reads that indicates a healthy rangefinder 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) 95 #ifndef THR_SURFACE_TRACKING_VELZ_MAX 96 # define THR_SURFACE_TRACKING_VELZ_MAX 150 // max vertical speed change while surface tracking with rangefinder 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 103 #ifndef RANGEFINDER_WPNAV_FILT_HZ 104 # define RANGEFINDER_WPNAV_FILT_HZ 0.25f // filter frequency for rangefinder altitude provided to waypoint navigation class 107 #ifndef RANGEFINDER_TILT_CORRECTION // by disable tilt correction for use of range finder data by EKF 108 # define RANGEFINDER_TILT_CORRECTION ENABLED 111 #ifndef RANGEFINDER_GLITCH_ALT_CM 112 # define RANGEFINDER_GLITCH_ALT_CM 200 // amount of rangefinder change to be considered a glitch 115 #ifndef RANGEFINDER_GLITCH_NUM_SAMPLES 116 # define RANGEFINDER_GLITCH_NUM_SAMPLES 3 // number of rangefinder glitches in a row to take new reading 122 #ifndef PROXIMITY_ENABLED 123 # define PROXIMITY_ENABLED ENABLED 126 #ifndef MAV_SYSTEM_ID 127 # define MAV_SYSTEM_ID 1 134 #ifndef BOARD_VOLTAGE_MIN 135 # define BOARD_VOLTAGE_MIN 4.3f // min board voltage in volts for pre-arm checks 138 #ifndef BOARD_VOLTAGE_MAX 139 # define BOARD_VOLTAGE_MAX 5.8f // max board voltage in volts for pre-arm checks 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 149 # define FS_GCS DISABLED 151 #ifndef FS_GCS_TIMEOUT_MS 152 # define FS_GCS_TIMEOUT_MS 5000 // gcs failsafe triggers after 5 seconds with no GCS heartbeat 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 161 #ifndef FS_RADIO_TIMEOUT_MS 162 #define FS_RADIO_TIMEOUT_MS 500 // RC Radio Failsafe triggers after 500 miliseconds with No RC Input 166 #ifndef FS_TERRAIN_TIMEOUT_MS 167 #define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL) 170 #ifndef PREARM_DISPLAY_PERIOD 171 # define PREARM_DISPLAY_PERIOD 30 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 181 #ifndef FS_EKF_ACTION_DEFAULT 182 # define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_LAND // EKF failsafe triggers land by default 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 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 195 # define MAGNETOMETER ENABLED 198 #ifndef COMPASS_CAL_STICK_GESTURE_TIME 199 #define COMPASS_CAL_STICK_GESTURE_TIME 2.0f // 2 seconds 201 #ifndef COMPASS_CAL_STICK_DELAY 202 #define COMPASS_CAL_STICK_DELAY 5.0f 208 # define OPTFLOW ENABLED 210 #ifndef VISUAL_ODOMETRY_ENABLED 211 # define VISUAL_ODOMETRY_ENABLED !HAL_MINIMIZE_FEATURES 216 #ifndef AUTOTUNE_ENABLED 217 # define AUTOTUNE_ENABLED ENABLED 223 # define SPRAYER !HAL_MINIMIZE_FEATURES 228 #ifndef PRECISION_LANDING 229 # define PRECISION_LANDING ENABLED 234 #ifndef GRIPPER_ENABLED 235 # define GRIPPER_ENABLED !HAL_MINIMIZE_FEATURES 240 #ifndef WINCH_ENABLED 241 # define WINCH_ENABLED !HAL_MINIMIZE_FEATURES 247 # define RPM_ENABLED ENABLED 253 # define PARACHUTE ENABLED 259 # define ADSB_ENABLED !HAL_MINIMIZE_FEATURES 265 # define NAV_GUIDED !HAL_MINIMIZE_FEATURES 270 #ifndef MODE_ACRO_ENABLED 271 # define MODE_ACRO_ENABLED ENABLED 276 #ifndef MODE_AUTO_ENABLED 277 # define MODE_AUTO_ENABLED ENABLED 282 #ifndef MODE_BRAKE_ENABLED 283 # define MODE_BRAKE_ENABLED ENABLED 288 #ifndef MODE_CIRCLE_ENABLED 289 # define MODE_CIRCLE_ENABLED ENABLED 294 #ifndef MODE_DRIFT_ENABLED 295 # define MODE_DRIFT_ENABLED ENABLED 300 #ifndef MODE_FOLLOW_ENABLED 301 # define MODE_FOLLOW_ENABLED !HAL_MINIMIZE_FEATURES 306 #ifndef MODE_GUIDED_ENABLED 307 # define MODE_GUIDED_ENABLED ENABLED 312 #ifndef MODE_GUIDED_NOGPS_ENABLED 313 # define MODE_GUIDED_NOGPS_ENABLED ENABLED 318 #ifndef MODE_LOITER_ENABLED 319 # define MODE_LOITER_ENABLED ENABLED 324 #ifndef MODE_POSHOLD_ENABLED 325 # define MODE_POSHOLD_ENABLED ENABLED 330 #ifndef MODE_RTL_ENABLED 331 # define MODE_RTL_ENABLED ENABLED 336 #ifndef MODE_SMARTRTL_ENABLED 337 # define MODE_SMARTRTL_ENABLED ENABLED 342 #ifndef MODE_SPORT_ENABLED 343 # define MODE_SPORT_ENABLED !HAL_MINIMIZE_FEATURES 348 #ifndef MODE_THROW_ENABLED 349 # define MODE_THROW_ENABLED ENABLED 354 #ifndef BEACON_ENABLED 355 # define BEACON_ENABLED !HAL_MINIMIZE_FEATURES 368 #ifndef FLIGHT_MODE_1 369 # define FLIGHT_MODE_1 STABILIZE 371 #ifndef FLIGHT_MODE_2 372 # define FLIGHT_MODE_2 STABILIZE 374 #ifndef FLIGHT_MODE_3 375 # define FLIGHT_MODE_3 STABILIZE 377 #ifndef FLIGHT_MODE_4 378 # define FLIGHT_MODE_4 STABILIZE 380 #ifndef FLIGHT_MODE_5 381 # define FLIGHT_MODE_5 STABILIZE 383 #ifndef FLIGHT_MODE_6 384 # define FLIGHT_MODE_6 STABILIZE 391 #ifndef FS_THR_VALUE_DEFAULT 392 # define FS_THR_VALUE_DEFAULT 975 398 #ifndef PILOT_TKOFF_ALT_DEFAULT 399 # define PILOT_TKOFF_ALT_DEFAULT 0 // default final alt above home for pilot initiated takeoff 407 # define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s 409 #ifndef LAND_REPOSITION_DEFAULT 410 # define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing 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 415 #ifndef LAND_CANCEL_TRIGGER_THR 416 # define LAND_CANCEL_TRIGGER_THR 700 // land is cancelled by input throttle above 700 418 #ifndef LAND_RANGEFINDER_MIN_ALT_CM 419 #define LAND_RANGEFINDER_MIN_ALT_CM 200 425 #ifndef LAND_DETECTOR_TRIGGER_SEC 426 # define LAND_DETECTOR_TRIGGER_SEC 1.0f // number of seconds to detect a landing 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) 431 #ifndef LAND_DETECTOR_ACCEL_LPF_CUTOFF 432 # define LAND_DETECTOR_ACCEL_LPF_CUTOFF 1.0f // frequency cutoff of land detector accelerometer filter 434 #ifndef LAND_DETECTOR_ACCEL_MAX 435 # define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s 442 # define CAMERA ENABLED 449 # define MOUNT ENABLED 459 # define ACRO_RP_P 4.5f 463 # define ACRO_YAW_P 4.5f 466 #ifndef ACRO_LEVEL_MAX_ANGLE 467 # define ACRO_LEVEL_MAX_ANGLE 3000 470 #ifndef ACRO_BALANCE_ROLL 471 #define ACRO_BALANCE_ROLL 1.0f 474 #ifndef ACRO_BALANCE_PITCH 475 #define ACRO_BALANCE_PITCH 1.0f 478 #ifndef ACRO_RP_EXPO_DEFAULT 479 #define ACRO_RP_EXPO_DEFAULT 0.3f 482 #ifndef ACRO_Y_EXPO_DEFAULT 483 #define ACRO_Y_EXPO_DEFAULT 0.0f 486 #ifndef ACRO_THR_MID_DEFAULT 487 #define ACRO_THR_MID_DEFAULT 0.0f 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. 496 # define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude 500 # define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m) 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 507 #ifndef RTL_ABS_MIN_CLIMB 508 # define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb 511 #ifndef RTL_CONE_SLOPE_DEFAULT 512 # define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone 515 #ifndef RTL_MIN_CONE_SLOPE 516 # define RTL_MIN_CONE_SLOPE 0.5f // minimum slope of cone 519 #ifndef RTL_LOITER_TIME 520 # define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before beginning final descent 524 #ifndef WP_YAW_BEHAVIOR_DEFAULT 525 # define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 528 #ifndef AUTO_YAW_SLEW_RATE 529 # define AUTO_YAW_SLEW_RATE 60 // degrees/sec 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 537 #ifndef SUPER_SIMPLE_RADIUS 538 # define SUPER_SIMPLE_RADIUS 1000 544 #ifndef ROLL_PITCH_YAW_INPUT_MAX 545 # define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range 547 #ifndef DEFAULT_ANGLE_MAX 548 # define DEFAULT_ANGLE_MAX 4500 // ANGLE_MAX parameters default value 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 557 #ifndef BRAKE_MODE_SPEED_Z 558 # define BRAKE_MODE_SPEED_Z 250 // z-axis speed in cm/s in Brake Mode 560 #ifndef BRAKE_MODE_DECEL_RATE 561 # define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode 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 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 578 #ifndef THR_DZ_DEFAULT 579 # define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter 583 #ifndef PILOT_VELZ_MAX 584 # define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s 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 591 #ifndef ALT_HOLD_INIT_MAX_OVERSHOOT 592 # define ALT_HOLD_INIT_MAX_OVERSHOOT 200 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 599 #ifndef AUTO_DISARMING_DELAY 600 # define AUTO_DISARMING_DELAY 10 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) 609 #ifndef THROW_VERTICAL_SPEED 610 # define THROW_VERTICAL_SPEED 50.0f // motors start when vehicle reaches this total 3D speed in cm/s 616 #ifndef LOGGING_ENABLED 617 # define LOGGING_ENABLED ENABLED 621 #ifndef DEFAULT_LOG_BITMASK 622 # define DEFAULT_LOG_BITMASK \ 623 MASK_LOG_ATTITUDE_MED | \ 645 #define AC_FENCE ENABLED 649 #define AC_RALLY ENABLED 653 #define AC_TERRAIN ENABLED 656 #if AC_TERRAIN && !AC_RALLY 657 #error Terrain relies on Rally which is disabled 660 #ifndef AC_AVOID_ENABLED 661 #define AC_AVOID_ENABLED ENABLED 664 #if AC_AVOID_ENABLED && !PROXIMITY_ENABLED 665 #error AC_Avoidance relies on PROXIMITY_ENABLED which is disabled 667 #if AC_AVOID_ENABLED && !AC_FENCE 668 #error AC_Avoidance relies on AC_FENCE which is disabled 671 #if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED 672 #error Follow Mode relies on AC_AVOID which is disabled 675 #if MODE_AUTO_ENABLED && !MODE_GUIDED_ENABLED 676 #error ModeAuto requires ModeGuided which is disabled 679 #if MODE_AUTO_ENABLED && !MODE_CIRCLE_ENABLED 680 #error ModeAuto requires ModeCircle which is disabled 683 #if MODE_AUTO_ENABLED && !MODE_RTL_ENABLED 684 #error ModeAuto requires ModeRTL which is disabled 687 #if AC_TERRAIN && !MODE_AUTO_ENABLED 688 #error Terrain requires ModeAuto which is disabled 691 #if FRAME_CONFIG == HELI_FRAME && !MODE_ACRO_ENABLED 692 #error Helicopter frame requires acro mode support which is disabled 700 #ifndef FRSKY_TELEM_ENABLED 701 # define FRSKY_TELEM_ENABLED ENABLED 704 #ifndef ADVANCED_FAILSAFE 705 # define ADVANCED_FAILSAFE DISABLED 708 #ifndef CH_MODE_DEFAULT 709 # define CH_MODE_DEFAULT 5 712 #ifndef TOY_MODE_ENABLED 713 #define TOY_MODE_ENABLED DISABLED 716 #if TOY_MODE_ENABLED && FRAME_CONFIG == HELI_FRAME 717 #error Toy mode is not available on Helicopters 720 #ifndef STATS_ENABLED 721 # define STATS_ENABLED ENABLED 724 #ifndef DEVO_TELEM_ENABLED 725 #if HAL_MINIMIZE_FEATURES 726 #define DEVO_TELEM_ENABLED DISABLED 728 #define DEVO_TELEM_ENABLED ENABLED