ardupilot/ArduCopter/config.h

1078 lines
28 KiB
C
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
#ifndef __ARDUCOPTER_CONFIG_H__
#define __ARDUCOPTER_CONFIG_H__
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
//
// DO NOT EDIT this file to adjust your configuration. Create your own
// APM_Config.h and use APM_Config.h.example as a reference.
//
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
///
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//
// Default and automatic configuration details.
//
// Notes for maintainers:
//
// - Try to keep this file organised in the same order as APM_Config.h.example
//
#include "defines.h"
///
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
/// change in your local copy of APM_Config.h.
///
#ifdef USE_CMAKE_APM_CONFIG
2012-08-21 23:19:50 -03:00
#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists
#else
2012-08-21 23:19:50 -03:00
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// HARDWARE CONFIGURATION AND CONNECTIONS
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// APM HARDWARE
//
#ifndef CONFIG_APM_HARDWARE
2012-08-21 23:19:50 -03:00
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
#endif
//////////////////////////////////////////////////////////////////////////////
2011-11-25 19:11:25 -04:00
// APM2 HARDWARE DEFAULTS
//
2011-11-25 19:11:25 -04:00
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
2012-08-21 23:19:50 -03:00
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
# ifdef APM2_BETA_HARDWARE
# define CONFIG_BARO AP_BARO_BMP085
# else // APM2 Production Hardware (default)
# define CONFIG_BARO AP_BARO_MS5611
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// FRAME_CONFIG
//
#ifndef FRAME_CONFIG
2012-08-21 23:19:50 -03:00
# define FRAME_CONFIG QUAD_FRAME
#endif
#ifndef FRAME_ORIENTATION
2012-08-21 23:19:50 -03:00
# define FRAME_ORIENTATION X_FRAME
#endif
#ifndef TOY_EDF
2012-08-21 23:19:50 -03:00
# define TOY_EDF DISABLED
#endif
#ifndef TOY_MIXER
2012-08-21 23:19:50 -03:00
# define TOY_MIXER TOY_LINEAR_MIXER
#endif
//////////////////////////////////////////////////////////////////////////////
// IMU Selection
//
#ifndef CONFIG_IMU_TYPE
2012-08-21 23:19:50 -03:00
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
#endif
#if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
# define NUM_IMU_SAMPLES_FOR_200HZ 5
# define NUM_IMU_SAMPLES_FOR_100HZ 10
# define NUM_IMU_SAMPLES_FOR_50HZ 20
#endif
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
# define NUM_IMU_SAMPLES_FOR_200HZ 1
# define NUM_IMU_SAMPLES_FOR_100HZ 2
# define NUM_IMU_SAMPLES_FOR_50HZ 4
#endif
//////////////////////////////////////////////////////////////////////////////
// ADC Enable - used to eliminate for systems which don't have ADC.
//
#ifndef CONFIG_ADC
2012-08-21 23:19:50 -03:00
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
# define CONFIG_ADC ENABLED
# else
# define CONFIG_ADC DISABLED
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// PWM control
// default RC speed in Hz
#ifndef RC_FAST_SPEED
2012-08-21 23:19:50 -03:00
# if FRAME_CONFIG == HELI_FRAME
# define RC_FAST_SPEED 125
# else
# define RC_FAST_SPEED 490
# endif
#endif
2012-05-15 11:07:03 -03:00
////////////////////////////////////////////////////////
// LED and IO Pins
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
2012-08-21 23:19:50 -03:00
# define A_LED_PIN 37
# define B_LED_PIN 36
# define C_LED_PIN 35
# define LED_ON HIGH
# define LED_OFF LOW
# define SLIDE_SWITCH_PIN 40
# define PUSHBUTTON_PIN 41
# define USB_MUX_PIN -1
# define CLI_SLIDER_ENABLED DISABLED
# define OPTFLOW_CS_PIN 34
# define BATTERY_PIN_1 0
# define CURRENT_PIN_1 1
2011-11-25 19:11:25 -04:00
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
2012-08-21 23:19:50 -03:00
# define A_LED_PIN 27
# define B_LED_PIN 26
# define C_LED_PIN 25
# define LED_ON LOW
# define LED_OFF HIGH
# define SLIDE_SWITCH_PIN (-1)
# define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED
# define USB_MUX_PIN 23
# define OPTFLOW_CS_PIN A3
# define BATTERY_PIN_1 1
# define CURRENT_PIN_1 2
#endif
2012-05-15 11:07:03 -03:00
////////////////////////////////////////////////////////////////////////////////
// CopterLEDs
//
#ifndef COPTER_LEDS
2012-08-21 23:19:50 -03:00
#define COPTER_LEDS ENABLED
#endif
2012-08-21 23:19:50 -03:00
#define COPTER_LED_ON HIGH
#define COPTER_LED_OFF LOW
2012-05-15 11:07:03 -03:00
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
2012-08-21 23:19:50 -03:00
#define COPTER_LED_1 AN4 // Motor or Aux LED
#define COPTER_LED_2 AN5 // Motor LED or Beeper
#define COPTER_LED_3 AN6 // Motor or GPS LED
#define COPTER_LED_4 AN7 // Motor LED
#define COPTER_LED_5 AN8 // Motor LED
#define COPTER_LED_6 AN9 // Motor LED
#define COPTER_LED_7 AN10 // Motor LED
#define COPTER_LED_8 AN11 // Motor LED
2012-05-15 11:07:03 -03:00
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
2012-08-21 23:19:50 -03:00
#define COPTER_LED_1 AN8 // Motor or Aux LED
#define COPTER_LED_2 AN9 // Motor LED
#define COPTER_LED_3 AN10 // Motor or GPS LED
#define COPTER_LED_4 AN11 // Motor LED
#define COPTER_LED_5 AN12 // Motor LED
#define COPTER_LED_6 AN13 // Motor LED
#define COPTER_LED_7 AN14 // Motor LED
#define COPTER_LED_8 AN15 // Motor LED
2012-05-15 11:07:03 -03:00
#endif
//////////////////////////////////////////////////////////////////////////////
// Pushbutton & Relay
//
#ifndef CONFIG_PUSHBUTTON
2012-08-21 23:19:50 -03:00
# define CONFIG_PUSHBUTTON ENABLED
#endif
#ifndef CONFIG_RELAY
2012-08-21 23:19:50 -03:00
# define CONFIG_RELAY ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Barometer
//
#ifndef CONFIG_BARO
2012-08-21 23:19:50 -03:00
# define CONFIG_BARO AP_BARO_BMP085
#endif
//////////////////////////////////////////////////////////////////////////////
// Sonar
//
#ifndef CONFIG_SONAR_SOURCE
2012-08-21 23:19:50 -03:00
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ADC
#endif
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC && CONFIG_ADC == DISABLED
2012-08-21 23:19:50 -03:00
# warning Cannot use ADC for CONFIG_SONAR_SOURCE, becaude CONFIG_ADC is DISABLED
# warning Defaulting CONFIG_SONAR_SOURCE to ANALOG_PIN
# undef CONFIG_SONAR_SOURCE
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
#endif
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
2012-08-21 23:19:50 -03:00
# ifndef CONFIG_SONAR_SOURCE_ADC_CHANNEL
# define CONFIG_SONAR_SOURCE_ADC_CHANNEL 7
# endif
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
2012-08-21 23:19:50 -03:00
# ifndef CONFIG_SONAR_SOURCE_ANALOG_PIN
# define CONFIG_SONAR_SOURCE_ANALOG_PIN A0
# endif
#else
2012-08-21 23:19:50 -03:00
# warning Invalid value for CONFIG_SONAR_SOURCE, disabling sonar
# undef SONAR_ENABLED
# define SONAR_ENABLED DISABLED
#endif
#ifndef CONFIG_SONAR
2012-08-21 23:19:50 -03:00
# define CONFIG_SONAR ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Channel Config (custom MOT channel mappings)
//
#ifndef CONFIG_CHANNELS
2012-08-21 23:19:50 -03:00
# define CONFIG_CHANNELS CHANNEL_CONFIG_DEFAULT
#endif
//////////////////////////////////////////////////////////////////////////////
// Acrobatics
//
#ifndef CH7_OPTION
2012-08-21 23:19:50 -03:00
# define CH7_OPTION CH7_SAVE_WP
#endif
//////////////////////////////////////////////////////////////////////////////
// HIL_MODE OPTIONAL
#ifndef HIL_MODE
2012-08-21 23:19:50 -03:00
#define HIL_MODE HIL_MODE_DISABLED
#endif
2012-08-21 23:19:50 -03:00
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
# undef GPS_PROTOCOL
# define GPS_PROTOCOL GPS_PROTOCOL_NONE
2011-12-11 23:59:39 -04:00
#undef CONFIG_SONAR
#define CONFIG_SONAR DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// GPS_PROTOCOL
//
#ifndef GPS_PROTOCOL
2012-08-21 23:19:50 -03:00
# define GPS_PROTOCOL GPS_PROTOCOL_AUTO
#endif
#ifndef MAV_SYSTEM_ID
2012-08-21 23:19:50 -03:00
# define MAV_SYSTEM_ID 1
#endif
//////////////////////////////////////////////////////////////////////////////
// Serial port speeds.
//
#ifndef SERIAL0_BAUD
2012-08-21 23:19:50 -03:00
# define SERIAL0_BAUD 115200
#endif
#ifndef SERIAL3_BAUD
2012-08-21 23:19:50 -03:00
# define SERIAL3_BAUD 57600
#endif
//////////////////////////////////////////////////////////////////////////////
// Battery monitoring
//
#ifndef BATTERY_EVENT
2012-08-21 23:19:50 -03:00
# define BATTERY_EVENT DISABLED
#endif
#ifndef LOW_VOLTAGE
2012-08-21 23:19:50 -03:00
# define LOW_VOLTAGE 9.6
#endif
#ifndef VOLT_DIV_RATIO
2012-08-21 23:19:50 -03:00
# define VOLT_DIV_RATIO 3.56
#endif
#ifndef CURR_AMP_PER_VOLT
2012-08-21 23:19:50 -03:00
# define CURR_AMP_PER_VOLT 27.32
#endif
#ifndef CURR_AMPS_OFFSET
2012-08-21 23:19:50 -03:00
# define CURR_AMPS_OFFSET 0.0
#endif
#ifndef HIGH_DISCHARGE
2012-08-21 23:19:50 -03:00
# define HIGH_DISCHARGE 1760
2011-09-18 21:12:28 -03:00
#endif
2012-05-15 11:07:03 -03:00
//////////////////////////////////////////////////////////////////////////////
// INPUT_VOLTAGE
//
#ifndef INPUT_VOLTAGE
2012-08-21 23:19:50 -03:00
# define INPUT_VOLTAGE 5.0
#endif
//////////////////////////////////////////////////////////////////////////////
// MAGNETOMETER
#ifndef MAGNETOMETER
2012-08-21 23:19:50 -03:00
# define MAGNETOMETER ENABLED
#endif
#ifndef MAG_ORIENTATION
2012-08-21 23:19:50 -03:00
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#endif
//////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW
2012-08-21 23:19:50 -03:00
#if defined( __AVR_ATmega2560__ ) // determines if optical flow code is included
#define OPTFLOW_ENABLED
#endif
2012-08-21 23:19:50 -03:00
#ifndef OPTFLOW // sets global enabled/disabled flag for optflow (as seen in CLI)
# define OPTFLOW DISABLED
#endif
#ifndef OPTFLOW_ORIENTATION
2012-08-21 23:19:50 -03:00
# define OPTFLOW_ORIENTATION AP_OPTICALFLOW_ADNS3080_PINS_FORWARD
#endif
#ifndef OPTFLOW_RESOLUTION
2012-08-21 23:19:50 -03:00
# define OPTFLOW_RESOLUTION ADNS3080_RESOLUTION_1600
#endif
#ifndef OPTFLOW_FOV
2012-08-21 23:19:50 -03:00
# define OPTFLOW_FOV AP_OPTICALFLOW_ADNS3080_08_FOV
#endif
// optical flow based loiter PI values
#ifndef OPTFLOW_ROLL_P
2012-08-21 23:19:50 -03:00
#define OPTFLOW_ROLL_P 2.5
#endif
#ifndef OPTFLOW_ROLL_I
2012-08-21 23:19:50 -03:00
#define OPTFLOW_ROLL_I 3.2
#endif
#ifndef OPTFLOW_ROLL_D
2012-08-21 23:19:50 -03:00
#define OPTFLOW_ROLL_D 0.12
#endif
#ifndef OPTFLOW_PITCH_P
2012-08-21 23:19:50 -03:00
#define OPTFLOW_PITCH_P 2.5
#endif
#ifndef OPTFLOW_PITCH_I
2012-08-21 23:19:50 -03:00
#define OPTFLOW_PITCH_I 3.2
#endif
#ifndef OPTFLOW_PITCH_D
2012-08-21 23:19:50 -03:00
#define OPTFLOW_PITCH_D 0.12
#endif
#ifndef OPTFLOW_IMAX
2012-08-21 23:19:50 -03:00
#define OPTFLOW_IMAX 4
#endif
//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// FLIGHT_MODE
//
#if !defined(FLIGHT_MODE_1)
2012-08-21 23:19:50 -03:00
# define FLIGHT_MODE_1 STABILIZE
#endif
#if !defined(FLIGHT_MODE_2)
2012-08-21 23:19:50 -03:00
# define FLIGHT_MODE_2 STABILIZE
#endif
#if !defined(FLIGHT_MODE_3)
2012-08-21 23:19:50 -03:00
# define FLIGHT_MODE_3 STABILIZE
#endif
#if !defined(FLIGHT_MODE_4)
2012-08-21 23:19:50 -03:00
# define FLIGHT_MODE_4 STABILIZE
#endif
#if !defined(FLIGHT_MODE_5)
2012-08-21 23:19:50 -03:00
# define FLIGHT_MODE_5 STABILIZE
#endif
#if !defined(FLIGHT_MODE_6)
2012-08-21 23:19:50 -03:00
# define FLIGHT_MODE_6 STABILIZE
#endif
//////////////////////////////////////////////////////////////////////////////
// THROTTLE_FAILSAFE
// THROTTLE_FS_VALUE
// THROTTLE_FAILSAFE_ACTION
//
#ifndef THROTTLE_FAILSAFE
2012-08-21 23:19:50 -03:00
# define THROTTLE_FAILSAFE DISABLED
#endif
#ifndef THROTTE_FS_VALUE
2012-08-21 23:19:50 -03:00
# define THROTTLE_FS_VALUE 975
#endif
#ifndef THROTTLE_FAILSAFE_ACTION
2012-08-21 23:19:50 -03:00
# define THROTTLE_FAILSAFE_ACTION 2
#endif
#ifndef MINIMUM_THROTTLE
2012-08-21 23:19:50 -03:00
# define MINIMUM_THROTTLE 130
#endif
2011-12-29 02:37:00 -04:00
#ifndef MAXIMUM_THROTTLE
2012-08-21 23:19:50 -03:00
# define MAXIMUM_THROTTLE 1000
2011-12-29 02:37:00 -04:00
#endif
#ifndef AUTO_LAND_TIME
2012-08-21 23:19:50 -03:00
# define AUTO_LAND_TIME 5
#endif
2011-12-29 02:37:00 -04:00
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// STARTUP BEHAVIOUR
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// GROUND_START_DELAY
//
#ifndef GROUND_START_DELAY
2012-08-21 23:19:50 -03:00
# define GROUND_START_DELAY 3
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// FLIGHT AND NAVIGATION CONTROL
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// Y6 Support
#ifndef TOP_BOTTOM_RATIO
2012-08-21 23:19:50 -03:00
# define TOP_BOTTOM_RATIO 1.00
#endif
//////////////////////////////////////////////////////////////////////////////
// CAMERA TRIGGER AND CONTROL
//
#ifndef CAMERA
2012-08-21 23:19:50 -03:00
# if defined( __AVR_ATmega1280__ )
# define CAMERA DISABLED
# else
# define CAMERA ENABLED
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// MOUNT (ANTENNA OR CAMERA)
//
#ifndef MOUNT
2012-08-21 23:19:50 -03:00
# if defined( __AVR_ATmega1280__ )
# define MOUNT DISABLED
# else
# define MOUNT ENABLED
# endif
#endif
2012-08-08 17:16:48 -03:00
#ifndef MOUNT2
2012-08-21 23:19:50 -03:00
# define MOUNT2 DISABLED
2012-08-08 17:16:48 -03:00
#endif
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED || MOUNT2 == ENABLED)
2012-08-21 23:19:50 -03:00
# warning "You choose to enable MOUNT on a small ATmega1280, CLI, CAMERA and AP_LIMITS will be disabled to free some space for it"
2012-08-04 13:38:50 -03:00
// The small ATmega1280 chip does not have enough memory for mount support
// so disable CLI, this will allow mount support and other improvements to fit.
// This should almost have no side effects, because the APM planner can now do a complete board setup.
2012-08-21 23:19:50 -03:00
# define CLI_ENABLED DISABLED
2012-08-04 13:38:50 -03:00
// The small ATmega1280 chip does not have enough memory for mount support
// so disable AUTO GPS support, this will allow mount support and other improvements to fit.
// This should almost have no side effects, because the most users use MTK anyways.
// If the user defined a GPS protocol, than we will NOT overwrite it
2012-08-21 23:19:50 -03:00
# if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
# undef GPS_PROTOCOL
# define GPS_PROTOCOL GPS_PROTOCOL_MTK
# endif
2012-08-04 13:38:50 -03:00
2012-08-05 18:05:52 -03:00
// To save some more space
2012-08-21 23:19:50 -03:00
# undef CAMERA
# define CAMERA DISABLED
# define AP_LIMITS DISABLED
2012-08-05 18:05:52 -03:00
#endif
//////////////////////////////////////////////////////////////////////////////
// Attitude Control
//
// Alt Hold Mode
#ifndef ALT_HOLD_YAW
2012-08-21 23:19:50 -03:00
# define ALT_HOLD_YAW YAW_HOLD
#endif
#ifndef ALT_HOLD_RP
2012-08-21 23:19:50 -03:00
# define ALT_HOLD_RP ROLL_PITCH_STABLE
#endif
#ifndef ALT_HOLD_THR
2012-08-21 23:19:50 -03:00
# define ALT_HOLD_THR THROTTLE_HOLD
#endif
// AUTO Mode
#ifndef AUTO_YAW
2012-08-21 23:19:50 -03:00
# define AUTO_YAW YAW_AUTO
#endif
#ifndef AUTO_RP
2012-08-21 23:19:50 -03:00
# define AUTO_RP ROLL_PITCH_AUTO
#endif
#ifndef AUTO_THR
2012-08-21 23:19:50 -03:00
# define AUTO_THR THROTTLE_AUTO
#endif
// CIRCLE Mode
#ifndef CIRCLE_YAW
2012-08-21 23:19:50 -03:00
# define CIRCLE_YAW YAW_AUTO
#endif
#ifndef CIRCLE_RP
2012-08-21 23:19:50 -03:00
# define CIRCLE_RP ROLL_PITCH_AUTO
#endif
#ifndef CIRCLE_THR
2012-08-21 23:19:50 -03:00
# define CIRCLE_THR THROTTLE_HOLD
#endif
// LOITER Mode
#ifndef LOITER_YAW
2012-08-21 23:19:50 -03:00
# define LOITER_YAW YAW_HOLD
#endif
#ifndef LOITER_RP
2012-08-21 23:19:50 -03:00
# define LOITER_RP ROLL_PITCH_AUTO
#endif
#ifndef LOITER_THR
2012-08-21 23:19:50 -03:00
# define LOITER_THR THROTTLE_HOLD
#endif
// RTL Mode
#ifndef RTL_YAW
2012-08-21 23:19:50 -03:00
# define RTL_YAW YAW_HOLD
#endif
#ifndef RTL_RP
2012-08-21 23:19:50 -03:00
# define RTL_RP ROLL_PITCH_AUTO
#endif
#ifndef RTL_THR
2012-08-21 23:19:50 -03:00
# define RTL_THR THROTTLE_HOLD
#endif
#ifndef SUPER_SIMPLE
2012-08-21 23:19:50 -03:00
# define SUPER_SIMPLE DISABLED
#endif
#ifndef SUPER_SIMPLE_RADIUS
2012-08-21 23:19:50 -03:00
# define SUPER_SIMPLE_RADIUS 1000
#endif
2012-02-15 13:09:42 -04:00
// RTL Mode
#ifndef RTL_APPROACH_ALT
2012-08-21 23:19:50 -03:00
# define RTL_APPROACH_ALT 200 // cm!!!
#endif
#ifndef RTL_HOLD_ALT
2012-08-21 23:19:50 -03:00
# define RTL_HOLD_ALT 1500 // height to return to Home in CM, 0 = Maintain current altitude
2012-02-15 13:09:42 -04:00
#endif
// LOITER Mode
#ifndef OF_LOITER_YAW
2012-08-21 23:19:50 -03:00
# define OF_LOITER_YAW YAW_HOLD
#endif
#ifndef OF_LOITER_RP
2012-08-21 23:19:50 -03:00
# define OF_LOITER_RP ROLL_PITCH_STABLE_OF
#endif
#ifndef OF_LOITER_THR
2012-08-21 23:19:50 -03:00
# define OF_LOITER_THR THROTTLE_HOLD
#endif
//////////////////////////////////////////////////////////////////////////////
// Attitude Control
//
2011-10-21 00:41:52 -03:00
// Extra motor values that are changed from time to time by jani @ jDrones as software
// and charachteristics changes.
#ifdef MOTORS_JD880
2012-08-21 23:19:50 -03:00
# define STABILIZE_ROLL_P 3.7
# define STABILIZE_ROLL_I 0.0
# define STABILIZE_ROLL_IMAX 8.0 // degrees
# define STABILIZE_PITCH_P 3.7
# define STABILIZE_PITCH_I 0.0
# define STABILIZE_PITCH_IMAX 8.0 // degrees
2011-10-21 00:41:52 -03:00
#endif
2011-12-18 22:29:05 -04:00
#ifdef MOTORS_JD850
2012-08-21 23:19:50 -03:00
# define STABILIZE_ROLL_P 4.2
# define STABILIZE_ROLL_I 0.0
# define STABILIZE_ROLL_IMAX 8.0 // degrees
# define STABILIZE_PITCH_P 4.2
# define STABILIZE_PITCH_I 0.0
# define STABILIZE_PITCH_IMAX 8.0 // degrees
2011-12-18 22:29:05 -04:00
#endif
2012-02-18 18:23:21 -04:00
#ifndef ACRO_P
2012-08-21 23:19:50 -03:00
# define ACRO_P 4.5
#endif
2012-02-15 15:29:25 -04:00
2012-02-18 18:23:21 -04:00
#ifndef AXIS_LOCK_ENABLED
2012-08-21 23:19:50 -03:00
# define AXIS_LOCK_ENABLED DISABLED
2012-02-18 18:23:21 -04:00
#endif
2012-02-15 15:29:25 -04:00
2012-02-18 18:23:21 -04:00
#ifndef AXIS_LOCK_P
2012-08-21 23:19:50 -03:00
# define AXIS_LOCK_P .02
2012-02-15 15:29:25 -04:00
#endif
2012-02-11 19:27:50 -04:00
// Good for smaller payload motors.
#ifndef STABILIZE_ROLL_P
2012-08-21 23:19:50 -03:00
# define STABILIZE_ROLL_P 4.5
#endif
#ifndef STABILIZE_ROLL_I
# define STABILIZE_ROLL_I 0.05
#endif
#ifndef STABILIZE_ROLL_IMAX
2012-08-21 23:19:50 -03:00
# define STABILIZE_ROLL_IMAX 8.0 // degrees
#endif
#ifndef STABILIZE_PITCH_P
2012-08-21 23:19:50 -03:00
# define STABILIZE_PITCH_P 4.5
#endif
#ifndef STABILIZE_PITCH_I
# define STABILIZE_PITCH_I 0.05
#endif
#ifndef STABILIZE_PITCH_IMAX
2012-08-21 23:19:50 -03:00
# define STABILIZE_PITCH_IMAX 8.0 // degrees
#endif
#ifndef STABILIZE_YAW_P
2012-08-21 23:19:50 -03:00
# define STABILIZE_YAW_P 7.0 // increase for more aggressive Yaw Hold, decrease if it's bouncy
2011-10-27 15:55:13 -03:00
#endif
#ifndef STABILIZE_YAW_I
2012-08-21 23:19:50 -03:00
# define STABILIZE_YAW_I 0.02
2011-10-27 15:55:13 -03:00
#endif
#ifndef STABILIZE_YAW_IMAX
2012-08-21 23:19:50 -03:00
# define STABILIZE_YAW_IMAX 8.0 // degrees * 100
2011-10-27 15:55:13 -03:00
#endif
//////////////////////////////////////////////////////////////////////////////
// Stabilize Rate Control
//
#ifndef RATE_ROLL_P
2012-08-31 23:18:10 -03:00
# define RATE_ROLL_P 0.175
#endif
#ifndef RATE_ROLL_I
2012-08-21 23:19:50 -03:00
# define RATE_ROLL_I 0.0
#endif
#ifndef RATE_ROLL_D
# define RATE_ROLL_D 0.004
#endif
#ifndef RATE_ROLL_IMAX
2012-08-21 23:19:50 -03:00
# define RATE_ROLL_IMAX 5.0 // degrees
#endif
#ifndef RATE_PITCH_P
2012-08-31 23:18:10 -03:00
# define RATE_PITCH_P 0.175
#endif
#ifndef RATE_PITCH_I
2012-08-21 23:19:50 -03:00
# define RATE_PITCH_I 0.0
#endif
#ifndef RATE_PITCH_D
# define RATE_PITCH_D 0.004
#endif
#ifndef RATE_PITCH_IMAX
2012-08-21 23:19:50 -03:00
# define RATE_PITCH_IMAX 5.0 // degrees
#endif
#ifndef RATE_YAW_P
2012-08-21 23:19:50 -03:00
# define RATE_YAW_P .25
#endif
#ifndef RATE_YAW_I
2012-08-21 23:19:50 -03:00
# define RATE_YAW_I 0.02
#endif
#ifndef RATE_YAW_D
2012-08-21 23:19:50 -03:00
# define RATE_YAW_D 0.000
#endif
#ifndef RATE_YAW_IMAX
2012-08-21 23:19:50 -03:00
# define RATE_YAW_IMAX 8.0 // degrees
#endif
2012-02-18 18:23:21 -04:00
#ifndef STABILIZE_D
2012-08-21 23:19:50 -03:00
# define STABILIZE_D 0.00
#endif
#ifndef STABILIZE_D_SCHEDULE
2012-08-21 23:19:50 -03:00
# define STABILIZE_D_SCHEDULE 0.5
2012-02-18 18:23:21 -04:00
#endif
//////////////////////////////////////////////////////////////////////////////
// Loiter control gains
//
#ifndef LOITER_P
2012-08-21 23:19:50 -03:00
# define LOITER_P .20
#endif
#ifndef LOITER_I
2012-08-21 23:19:50 -03:00
# define LOITER_I 0.0
#endif
#ifndef LOITER_IMAX
2012-08-21 23:19:50 -03:00
# define LOITER_IMAX 30 // degrees
#endif
2012-02-15 13:09:42 -04:00
//////////////////////////////////////////////////////////////////////////////
// Loiter Navigation control gains
//
#ifndef LOITER_RATE_P
# define LOITER_RATE_P 5.0 //
2012-02-15 13:09:42 -04:00
#endif
#ifndef LOITER_RATE_I
# define LOITER_RATE_I 0.04 // Wind control
2012-02-15 13:09:42 -04:00
#endif
#ifndef LOITER_RATE_D
2012-08-21 23:19:50 -03:00
# define LOITER_RATE_D 0.40 // try 2 or 3 for LOITER_RATE 1
2012-02-15 13:09:42 -04:00
#endif
#ifndef LOITER_RATE_IMAX
2012-08-21 23:19:50 -03:00
# define LOITER_RATE_IMAX 30 // degrees
2012-02-15 13:09:42 -04:00
#endif
//////////////////////////////////////////////////////////////////////////////
// WP Navigation control gains
//
#ifndef NAV_P
2012-08-21 23:19:50 -03:00
# define NAV_P 2.4 //
#endif
#ifndef NAV_I
2012-08-21 23:19:50 -03:00
# define NAV_I 0.17 // Wind control
#endif
#ifndef NAV_D
2012-08-21 23:19:50 -03:00
# define NAV_D 0.00 // .95
#endif
#ifndef NAV_IMAX
2012-08-21 23:19:50 -03:00
# define NAV_IMAX 18 // degrees
#endif
2012-02-15 13:09:42 -04:00
#ifndef AUTO_SLEW_RATE
2012-08-21 23:19:50 -03:00
# define AUTO_SLEW_RATE 30 // degrees
2012-02-15 13:09:42 -04:00
#endif
#ifndef WAYPOINT_SPEED_MAX
2012-08-21 23:19:50 -03:00
# define WAYPOINT_SPEED_MAX 500 // 6m/s error = 13mph
#endif
#ifndef WAYPOINT_SPEED_MIN
2012-08-21 23:19:50 -03:00
# define WAYPOINT_SPEED_MIN 150 // 1m/s
#endif
//////////////////////////////////////////////////////////////////////////////
// Throttle control gains
//
#ifndef AUTO_THROTTLE_HOLD
2012-08-21 23:19:50 -03:00
# define AUTO_THROTTLE_HOLD 1
#endif
#ifndef THROTTLE_CRUISE
2012-08-21 23:19:50 -03:00
# define THROTTLE_CRUISE 450 //
#endif
#ifndef ALT_HOLD_P
2012-08-21 23:19:50 -03:00
# define ALT_HOLD_P 0.3 // .5
#endif
#ifndef ALT_HOLD_I
2012-08-21 23:19:50 -03:00
# define ALT_HOLD_I 0.04
#endif
#ifndef ALT_HOLD_IMAX
2012-08-21 23:19:50 -03:00
# define ALT_HOLD_IMAX 300
#endif
// RATE control
#ifndef THROTTLE_P
2012-08-21 23:19:50 -03:00
# define THROTTLE_P 0.3 // .25
#endif
#ifndef THROTTLE_I
2012-08-21 23:19:50 -03:00
# define THROTTLE_I 0.03
#endif
#ifndef THROTTLE_D
2012-08-21 23:19:50 -03:00
# define THROTTLE_D 0.0
#endif
#ifndef THROTTLE_IMAX
2012-08-21 23:19:50 -03:00
# define THROTTLE_IMAX 300
#endif
//////////////////////////////////////////////////////////////////////////////
// Crosstrack compensation
//
#ifndef CROSSTRACK_GAIN
2012-08-21 23:19:50 -03:00
# define CROSSTRACK_GAIN .2
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// DEBUGGING
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// DEBUG_LEVEL
//
#ifndef DEBUG_LEVEL
2012-08-21 23:19:50 -03:00
# define DEBUG_LEVEL SEVERITY_LOW
#endif
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//
2011-12-23 22:44:30 -04:00
// Logging must be disabled for 1280 build.
#if defined( __AVR_ATmega1280__ )
2012-08-21 23:19:50 -03:00
# if LOGGING_ENABLED == ENABLED
2011-12-23 22:44:30 -04:00
// If logging was enabled in APM_Config or command line, warn the user.
2012-08-21 23:19:50 -03:00
# warning "Logging is not supported on ATmega1280"
# undef LOGGING_ENABLED
# endif
# ifndef LOGGING_ENABLED
# define LOGGING_ENABLED DISABLED
# endif
2011-12-23 22:44:30 -04:00
#elif !defined(LOGGING_ENABLED)
// Logging is enabled by default for all other builds.
2012-08-21 23:19:50 -03:00
# define LOGGING_ENABLED ENABLED
#endif
#ifndef LOG_ATTITUDE_FAST
2012-08-21 23:19:50 -03:00
# define LOG_ATTITUDE_FAST DISABLED
#endif
#ifndef LOG_ATTITUDE_MED
2012-08-21 23:19:50 -03:00
# define LOG_ATTITUDE_MED ENABLED
#endif
#ifndef LOG_GPS
2012-08-21 23:19:50 -03:00
# define LOG_GPS ENABLED
#endif
#ifndef LOG_PM
2012-08-21 23:19:50 -03:00
# define LOG_PM ENABLED
#endif
#ifndef LOG_CTUN
2012-08-21 23:19:50 -03:00
# define LOG_CTUN ENABLED
#endif
#ifndef LOG_NTUN
2012-08-21 23:19:50 -03:00
# define LOG_NTUN ENABLED
#endif
#ifndef LOG_MODE
2012-08-21 23:19:50 -03:00
# define LOG_MODE ENABLED
#endif
#ifndef LOG_RAW
2012-08-21 23:19:50 -03:00
# define LOG_RAW DISABLED
#endif
#ifndef LOG_CMD
2012-08-21 23:19:50 -03:00
# define LOG_CMD ENABLED
#endif
// current
#ifndef LOG_CUR
2012-08-21 23:19:50 -03:00
# define LOG_CUR DISABLED
#endif
// quad motor PWMs
#ifndef LOG_MOTORS
2012-08-21 23:19:50 -03:00
# define LOG_MOTORS DISABLED
#endif
// optical flow
#ifndef LOG_OPTFLOW
2012-08-21 23:19:50 -03:00
# define LOG_OPTFLOW DISABLED
#endif
#ifndef LOG_PID
2012-08-21 23:19:50 -03:00
# define LOG_PID DISABLED
#endif
// calculate the default log_bitmask
2012-08-21 23:19:50 -03:00
#define LOGBIT(_s) (LOG_ ## _s ? MASK_LOG_ ## _s : 0)
#define DEFAULT_LOG_BITMASK \
2012-08-21 23:19:50 -03:00
LOGBIT(ATTITUDE_FAST) | \
LOGBIT(ATTITUDE_MED) | \
LOGBIT(GPS) | \
LOGBIT(PM) | \
LOGBIT(CTUN) | \
LOGBIT(NTUN) | \
LOGBIT(MODE) | \
LOGBIT(RAW) | \
LOGBIT(CMD) | \
LOGBIT(CUR) | \
LOGBIT(MOTORS) | \
LOGBIT(OPTFLOW) | \
LOGBIT(PID)
// if we are using fast, Disable Medium
//#if LOG_ATTITUDE_FAST == ENABLED
// #undef LOG_ATTITUDE_MED
2012-08-21 23:19:50 -03:00
// #define LOG_ATTITUDE_MED DISABLED
//#endif
#ifndef DEBUG_PORT
2012-08-21 23:19:50 -03:00
# define DEBUG_PORT 0
#endif
#if DEBUG_PORT == 0
2012-08-21 23:19:50 -03:00
# define SendDebug_P(a) Serial.print_P(PSTR(a))
# define SendDebugln_P(a) Serial.println_P(PSTR(a))
# define SendDebug Serial.print
# define SendDebugln Serial.println
#elif DEBUG_PORT == 1
2012-08-21 23:19:50 -03:00
# define SendDebug_P(a) Serial1.print_P(PSTR(a))
# define SendDebugln_P(a) Serial1.println_P(PSTR(a))
# define SendDebug Serial1.print
# define SendDebugln Serial1.println
#elif DEBUG_PORT == 2
2012-08-21 23:19:50 -03:00
# define SendDebug_P(a) Serial2.print_P(PSTR(a))
# define SendDebugln_P(a) Serial2.println_P(PSTR(a))
# define SendDebug Serial2.print
# define SendDebugln Serial2.println
#elif DEBUG_PORT == 3
2012-08-21 23:19:50 -03:00
# define SendDebug_P(a) Serial3.print_P(PSTR(a))
# define SendDebugln_P(a) Serial3.println_P(PSTR(a))
# define SendDebug Serial3.print
# define SendDebugln Serial3.println
#endif
//////////////////////////////////////////////////////////////////////////////
// Navigation defaults
//
#ifndef WP_RADIUS_DEFAULT
2012-08-21 23:19:50 -03:00
# define WP_RADIUS_DEFAULT 2
#endif
#ifndef LOITER_RADIUS
2012-08-21 23:19:50 -03:00
# define LOITER_RADIUS 10 // meters for circle mode
#endif
#ifndef USE_CURRENT_ALT
2012-08-21 23:19:50 -03:00
# define USE_CURRENT_ALT FALSE
#endif
#ifndef CUT_MOTORS
2012-08-21 23:19:50 -03:00
# define CUT_MOTORS 1 // do we cut the motors with no throttle?
#endif
//////////////////////////////////////////////////////////////////////////////
// RC override
//
#ifndef ALLOW_RC_OVERRIDE
2012-08-21 23:19:50 -03:00
# define ALLOW_RC_OVERRIDE DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// AP_Limits Defaults
//
// Enable/disable AP_Limits
#ifndef AP_LIMITS
#define AP_LIMITS ENABLED
#endif
// Use PIN for displaying LIMITS status. 0 is disabled.
#ifndef LIMITS_TRIGGERED_PIN
#define LIMITS_TRIGGERED_PIN 0
#endif
// PWM of "on" state for LIM_CHANNEL
#ifndef LIMITS_ENABLE_PWM
#define LIMITS_ENABLE_PWM 1800
#endif
#ifndef LIM_ENABLED
#define LIM_ENABLED 0
#endif
#ifndef LIM_ALT_ON
#define LIM_ALT_ON 0
#endif
#ifndef LIM_FNC_ON
#define LIM_FNC_ON 0
#endif
#ifndef LIM_GPSLCK_ON
#define LIM_GPSLCK_ON 0
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//
// use this to completely disable the CLI
#ifndef CLI_ENABLED
// Sorry the chip is just too small to let this fit
2012-08-21 23:19:50 -03:00
# if defined( __AVR_ATmega1280__ )
# define CLI_ENABLED DISABLED
# else
# define CLI_ENABLED ENABLED
# endif
#endif
// use this to disable the CLI slider switch
#ifndef CLI_SLIDER_ENABLED
2012-08-21 23:19:50 -03:00
# define CLI_SLIDER_ENABLED DISABLED
#endif
// experimental mpu6000 DMP code
#ifndef DMP_ENABLED
2012-08-21 23:19:50 -03:00
# define DMP_ENABLED DISABLED
#endif
2012-04-23 02:16:41 -03:00
// experimental mpu6000 DMP code
#ifndef SECONDARY_DMP_ENABLED
# define SECONDARY_DMP_ENABLED DISABLED
#endif
#ifndef ALTERNATIVE_YAW_MODE
2012-08-21 23:19:50 -03:00
# define ALTERNATIVE_YAW_MODE DISABLED
#endif
// Inertia based contollers. disabled by default, work in progress
#define ACCEL_ALT_HOLD 0
#define INERTIAL_NAV DISABLED
#endif // __ARDUCOPTER_CONFIG_H__