ardupilot/ArduPlane/config.h

841 lines
22 KiB
C
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//
// 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:51 -03:00
#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists
#else
2012-08-21 23:19:51 -03:00
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
#endif
///
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
/// change in your local copy of APM_Config.h.
///
// Just so that it's completely clear...
2012-08-21 23:19:51 -03:00
#define ENABLED 1
#define DISABLED 0
// this avoids a very common config error
#define ENABLE ENABLED
#define DISABLE DISABLED
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// HARDWARE CONFIGURATION AND CONNECTIONS
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// APM HARDWARE
//
#ifndef CONFIG_APM_HARDWARE
2012-08-21 23:19:51 -03:00
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
#endif
2011-12-16 10:26:39 -04:00
#if defined( __AVR_ATmega1280__ )
2012-08-21 23:19:51 -03:00
#define LOGGING_ENABLED DISABLED
2011-12-16 10:26:39 -04:00
#endif
//////////////////////////////////////////////////////////////////////////////
2011-11-25 19:11:36 -04:00
// APM2 HARDWARE DEFAULTS
//
2011-11-25 19:11:36 -04:00
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
2012-08-21 23:19:51 -03:00
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define CONFIG_PITOT_SOURCE PITOT_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
// use this to enable telemetry on UART2. This is used
// when you have setup the solder bridge on an APM2 to enable UART2
#ifndef TELEMETRY_UART2
2012-08-21 23:19:51 -03:00
# define TELEMETRY_UART2 DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// LED and IO Pins
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
2012-08-21 23:19:51 -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 USB_MUX_PIN -1
# define CONFIG_RELAY ENABLED
# define BATTERY_PIN_1 0
# define CURRENT_PIN_1 1
2011-11-25 19:11:36 -04:00
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
2012-08-21 23:19:51 -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
#if TELEMETRY_UART2 == ENABLED
# define USB_MUX_PIN -1
#else
# define USB_MUX_PIN 23
#endif
# define BATTERY_PIN_1 1
# define CURRENT_PIN_1 2
#endif
2012-06-03 21:02:08 -03:00
//////////////////////////////////////////////////////////////////////////////
// IMU Selection
//
#ifndef CONFIG_IMU_TYPE
2012-08-21 23:19:51 -03:00
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
#endif
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
2012-08-21 23:19:51 -03:00
# ifndef CONFIG_MPU6000_CHIP_SELECT_PIN
# define CONFIG_MPU6000_CHIP_SELECT_PIN 53
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// ADC Enable - used to eliminate for systems which don't have ADC.
//
#ifndef CONFIG_ADC
2012-08-21 23:19:51 -03:00
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
# define CONFIG_ADC ENABLED
# else
# define CONFIG_ADC DISABLED
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// Barometer
//
#ifndef CONFIG_BARO
2012-08-21 23:19:51 -03:00
# define CONFIG_BARO AP_BARO_BMP085
#endif
//////////////////////////////////////////////////////////////////////////////
// Pitot
//
#ifndef PITOT_ENABLED
2012-08-21 23:19:51 -03:00
# define PITOT_ENABLED DISABLED
#endif
#ifndef CONFIG_PITOT_SOURCE
2012-08-21 23:19:51 -03:00
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ADC
#endif
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
2012-08-21 23:19:51 -03:00
# ifndef CONFIG_PITOT_SOURCE_ADC_CHANNEL
# define CONFIG_PITOT_SOURCE_ADC_CHANNEL 7
# endif
#elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
2012-08-21 23:19:51 -03:00
# ifndef CONFIG_PITOT_SOURCE_ANALOG_PIN
# define CONFIG_PITOT_SOURCE_ANALOG_PIN 0
# endif
#else
2012-08-21 23:19:51 -03:00
# warning Invalid value for CONFIG_PITOT_SOURCE, disabling airspeed
# undef PITOT_ENABLED
# define PITOT_ENABLED DISABLED
#endif
#ifndef SONAR_TYPE
2012-08-21 23:19:51 -03:00
# define SONAR_TYPE MAX_SONAR_LV // MAX_SONAR_XL,
#endif
#ifndef SONAR_ENABLED
2012-08-21 23:19:51 -03:00
#define SONAR_ENABLED DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// HIL_MODE OPTIONAL
#ifndef HIL_MODE
2012-08-21 23:19:51 -03:00
#define HIL_MODE HIL_MODE_DISABLED
#endif
2012-08-21 23:19:51 -03:00
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
# undef GPS_PROTOCOL
# define GPS_PROTOCOL GPS_PROTOCOL_NONE
#endif
//////////////////////////////////////////////////////////////////////////////
// GPS_PROTOCOL
//
// Note that this test must follow the HIL_PROTOCOL block as the HIL
// setup may override the GPS configuration.
//
#ifndef GPS_PROTOCOL
2012-08-21 23:19:51 -03:00
# define GPS_PROTOCOL GPS_PROTOCOL_AUTO
#endif
#ifndef MAV_SYSTEM_ID
2012-08-21 23:19:51 -03:00
# define MAV_SYSTEM_ID 1
#endif
//////////////////////////////////////////////////////////////////////////////
// Serial port speeds.
//
#ifndef SERIAL0_BAUD
2012-08-21 23:19:51 -03:00
# define SERIAL0_BAUD 115200
#endif
#ifndef SERIAL3_BAUD
2012-08-21 23:19:51 -03:00
# define SERIAL3_BAUD 57600
#endif
//////////////////////////////////////////////////////////////////////////////
// Battery monitoring
//
#ifndef BATTERY_EVENT
2012-08-21 23:19:51 -03:00
# define BATTERY_EVENT DISABLED
#endif
#ifndef LOW_VOLTAGE
2012-08-21 23:19:51 -03:00
# define LOW_VOLTAGE 9.6
#endif
#ifndef VOLT_DIV_RATIO
2012-08-21 23:19:51 -03:00
# define VOLT_DIV_RATIO 3.56 // This is the proper value for an on-board APM1 voltage divider with a 3.9kOhm resistor
//# define VOLT_DIV_RATIO 15.70 // This is the proper value for the AttoPilot 50V/90A sensor
//# define VOLT_DIV_RATIO 4.127 // This is the proper value for the AttoPilot 13.6V/45A sensor
#endif
#ifndef CURR_AMP_PER_VOLT
2012-08-21 23:19:51 -03:00
# define CURR_AMP_PER_VOLT 27.32 // This is the proper value for the AttoPilot 50V/90A sensor
//# define CURR_AMP_PER_VOLT 13.66 // This is the proper value for the AttoPilot 13.6V/45A sensor
#endif
#ifndef CURR_AMPS_OFFSET
2012-08-21 23:19:51 -03:00
# define CURR_AMPS_OFFSET 0.0
#endif
#ifndef HIGH_DISCHARGE
2012-08-21 23:19:51 -03:00
# define HIGH_DISCHARGE 1760
#endif
//////////////////////////////////////////////////////////////////////////////
// INPUT_VOLTAGE
//
#ifndef INPUT_VOLTAGE
2012-08-21 23:19:51 -03:00
# define INPUT_VOLTAGE 4.68 // 4.68 is the average value for a sample set. This is the value at the processor with 5.02 applied at the servo rail
#endif
//////////////////////////////////////////////////////////////////////////////
// MAGNETOMETER
#ifndef MAGNETOMETER
2012-08-21 23:19:51 -03:00
# define MAGNETOMETER DISABLED
#endif
#ifndef MAG_ORIENTATION
2012-08-21 23:19:51 -03:00
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// Radio channel limits
//
// Note that these are not called out in APM_Config.h.reference.
//
#ifndef CH5_MIN
2012-08-21 23:19:51 -03:00
# define CH5_MIN 1000
#endif
#ifndef CH5_MAX
2012-08-21 23:19:51 -03:00
# define CH5_MAX 2000
#endif
#ifndef CH6_MIN
2012-08-21 23:19:51 -03:00
# define CH6_MIN 1000
#endif
#ifndef CH6_MAX
2012-08-21 23:19:51 -03:00
# define CH6_MAX 2000
#endif
#ifndef CH7_MIN
2012-08-21 23:19:51 -03:00
# define CH7_MIN 1000
#endif
#ifndef CH7_MAX
2012-08-21 23:19:51 -03:00
# define CH7_MAX 2000
#endif
#ifndef CH8_MIN
2012-08-21 23:19:51 -03:00
# define CH8_MIN 1000
#endif
#ifndef CH8_MAX
2012-08-21 23:19:51 -03:00
# define CH8_MAX 2000
#endif
#ifndef FLAP_1_PERCENT
2012-08-21 23:19:51 -03:00
# define FLAP_1_PERCENT 0
#endif
#ifndef FLAP_1_SPEED
2012-08-21 23:19:51 -03:00
# define FLAP_1_SPEED 0
#endif
#ifndef FLAP_2_PERCENT
2012-08-21 23:19:51 -03:00
# define FLAP_2_PERCENT 0
#endif
#ifndef FLAP_2_SPEED
2012-08-21 23:19:51 -03:00
# define FLAP_2_SPEED 0
#endif
//////////////////////////////////////////////////////////////////////////////
// FLIGHT_MODE
// FLIGHT_MODE_CHANNEL
//
#ifndef FLIGHT_MODE_CHANNEL
2012-08-21 23:19:51 -03:00
# define FLIGHT_MODE_CHANNEL 8
#endif
#if (FLIGHT_MODE_CHANNEL != 5) && (FLIGHT_MODE_CHANNEL != 6) && (FLIGHT_MODE_CHANNEL != 7) && (FLIGHT_MODE_CHANNEL != 8)
2012-08-21 23:19:51 -03:00
# error XXX
# error XXX You must set FLIGHT_MODE_CHANNEL to 5, 6, 7 or 8
# error XXX
#endif
#if !defined(FLIGHT_MODE_1)
2012-08-21 23:19:51 -03:00
# define FLIGHT_MODE_1 RTL
#endif
#if !defined(FLIGHT_MODE_2)
2012-08-21 23:19:51 -03:00
# define FLIGHT_MODE_2 RTL
#endif
#if !defined(FLIGHT_MODE_3)
2012-08-21 23:19:51 -03:00
# define FLIGHT_MODE_3 STABILIZE
#endif
#if !defined(FLIGHT_MODE_4)
2012-08-21 23:19:51 -03:00
# define FLIGHT_MODE_4 STABILIZE
#endif
#if !defined(FLIGHT_MODE_5)
2012-08-21 23:19:51 -03:00
# define FLIGHT_MODE_5 MANUAL
#endif
#if !defined(FLIGHT_MODE_6)
2012-08-21 23:19:51 -03:00
# define FLIGHT_MODE_6 MANUAL
#endif
//////////////////////////////////////////////////////////////////////////////
// THROTTLE_FAILSAFE
// THROTTLE_FS_VALUE
// SHORT_FAILSAFE_ACTION
// LONG_FAILSAFE_ACTION
// GCS_HEARTBEAT_FAILSAFE
//
#ifndef THROTTLE_FAILSAFE
2012-08-21 23:19:51 -03:00
# define THROTTLE_FAILSAFE ENABLED
#endif
#ifndef THROTTLE_FS_VALUE
2012-08-21 23:19:51 -03:00
# define THROTTLE_FS_VALUE 950
#endif
#ifndef SHORT_FAILSAFE_ACTION
2012-08-21 23:19:51 -03:00
# define SHORT_FAILSAFE_ACTION 0
#endif
#ifndef LONG_FAILSAFE_ACTION
2012-08-21 23:19:51 -03:00
# define LONG_FAILSAFE_ACTION 0
#endif
#ifndef GCS_HEARTBEAT_FAILSAFE
2012-08-21 23:19:51 -03:00
# define GCS_HEARTBEAT_FAILSAFE DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// AUTO_TRIM
//
#ifndef AUTO_TRIM
2012-08-21 23:19:51 -03:00
# define AUTO_TRIM DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// THROTTLE_OUT
//
#ifndef THROTTE_OUT
2012-08-21 23:19:51 -03:00
# define THROTTLE_OUT ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// STARTUP BEHAVIOUR
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
2012-06-10 17:08:48 -03:00
//////////////////////////////////////////////////////////////////////////////
// Level with each startup = 0, level with MP/CLI only = 1
//
#ifndef MANUAL_LEVEL
2012-08-21 23:19:51 -03:00
# define MANUAL_LEVEL 0
2012-06-10 17:08:48 -03:00
#endif
//////////////////////////////////////////////////////////////////////////////
// GROUND_START_DELAY
//
#ifndef GROUND_START_DELAY
2012-08-21 23:19:51 -03:00
# define GROUND_START_DELAY 0
#endif
//////////////////////////////////////////////////////////////////////////////
// ENABLE_AIR_START
//
#ifndef ENABLE_AIR_START
2012-08-21 23:19:51 -03:00
# define ENABLE_AIR_START DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// ENABLE ELEVON_MIXING
//
#ifndef ELEVON_MIXING
2012-08-21 23:19:51 -03:00
# define ELEVON_MIXING DISABLED
#endif
#ifndef ELEVON_REVERSE
2012-08-21 23:19:51 -03:00
# define ELEVON_REVERSE DISABLED
#endif
#ifndef ELEVON_CH1_REVERSE
2012-08-21 23:19:51 -03:00
# define ELEVON_CH1_REVERSE DISABLED
#endif
#ifndef ELEVON_CH2_REVERSE
2012-08-21 23:19:51 -03:00
# define ELEVON_CH2_REVERSE DISABLED
#endif
2012-06-13 16:00:20 -03:00
//////////////////////////////////////////////////////////////////////////////
// CAMERA TRIGGER AND CONTROL
//
#ifndef CAMERA
2012-08-21 23:19:51 -03:00
# define CAMERA ENABLED
2012-06-13 16:00:20 -03:00
#endif
//////////////////////////////////////////////////////////////////////////////
// MOUNT (ANTENNA OR CAMERA)
//
#ifndef MOUNT
2012-08-21 23:19:51 -03:00
# define MOUNT ENABLED
#endif
#ifndef MOUNT2
2012-08-21 23:19:51 -03:00
# define MOUNT2 DISABLED
#endif
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED || MOUNT2 == ENABLED)
// 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:51 -03:00
# define CLI_ENABLED DISABLED
// 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:51 -03:00
# if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
# undef GPS_PROTOCOL
# define GPS_PROTOCOL GPS_PROTOCOL_MTK
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// FLIGHT AND NAVIGATION CONTROL
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// Altitude measurement and control.
//
#ifndef ALT_EST_GAIN
2012-08-21 23:19:51 -03:00
# define ALT_EST_GAIN 0.01
#endif
#ifndef ALTITUDE_MIX
2012-08-21 23:19:51 -03:00
# define ALTITUDE_MIX 1
#endif
//////////////////////////////////////////////////////////////////////////////
// AIRSPEED_CRUISE
//
#ifndef AIRSPEED_CRUISE
2012-08-21 23:19:51 -03:00
# define AIRSPEED_CRUISE 12 // 12 m/s
#endif
#define AIRSPEED_CRUISE_CM AIRSPEED_CRUISE*100
//////////////////////////////////////////////////////////////////////////////
// MIN_GNDSPEED
//
#ifndef MIN_GNDSPEED
2012-08-21 23:19:51 -03:00
# define MIN_GNDSPEED 0 // m/s (0 disables)
#endif
#define MIN_GNDSPEED_CM MIN_GNDSPEED*100
//////////////////////////////////////////////////////////////////////////////
// FLY_BY_WIRE_B airspeed control
//
#ifndef AIRSPEED_FBW_MIN
2012-08-21 23:19:51 -03:00
# define AIRSPEED_FBW_MIN 6
#endif
#ifndef AIRSPEED_FBW_MAX
2012-08-21 23:19:51 -03:00
# define AIRSPEED_FBW_MAX 22
#endif
#ifndef ALT_HOLD_FBW
2012-08-21 23:19:51 -03:00
# define ALT_HOLD_FBW 0
#endif
#define ALT_HOLD_FBW_CM ALT_HOLD_FBW*100
2012-03-11 17:30:09 -03:00
/* The following parameters have no corresponding control implementation
2012-08-21 23:19:51 -03:00
* #ifndef THROTTLE_ALT_P
# define THROTTLE_ALT_P 0.32
##endif
##ifndef THROTTLE_ALT_I
# define THROTTLE_ALT_I 0.0
##endif
##ifndef THROTTLE_ALT_D
# define THROTTLE_ALT_D 0.0
##endif
##ifndef THROTTLE_ALT_INT_MAX
# define THROTTLE_ALT_INT_MAX 20
##endif
##define THROTTLE_ALT_INT_MAX_CM THROTTLE_ALT_INT_MAX*100
*/
//////////////////////////////////////////////////////////////////////////////
// Servo Mapping
//
#ifndef THROTTLE_MIN
2012-08-21 23:19:51 -03:00
# define THROTTLE_MIN 0 // percent
#endif
#ifndef THROTTLE_CRUISE
2012-08-21 23:19:51 -03:00
# define THROTTLE_CRUISE 45
#endif
#ifndef THROTTLE_MAX
2012-08-21 23:19:51 -03:00
# define THROTTLE_MAX 75
#endif
//////////////////////////////////////////////////////////////////////////////
// Autopilot control limits
//
#ifndef HEAD_MAX
2012-08-21 23:19:51 -03:00
# define HEAD_MAX 45
#endif
#ifndef PITCH_MAX
2012-08-21 23:19:51 -03:00
# define PITCH_MAX 15
#endif
#ifndef PITCH_MIN
2012-08-21 23:19:51 -03:00
# define PITCH_MIN -25
#endif
#define HEAD_MAX_CENTIDEGREE HEAD_MAX * 100
#define PITCH_MAX_CENTIDEGREE PITCH_MAX * 100
#define PITCH_MIN_CENTIDEGREE PITCH_MIN * 100
//////////////////////////////////////////////////////////////////////////////
// Attitude control gains
//
#ifndef SERVO_ROLL_P
2012-08-21 23:19:51 -03:00
# define SERVO_ROLL_P 0.4
#endif
#ifndef SERVO_ROLL_I
2012-08-21 23:19:51 -03:00
# define SERVO_ROLL_I 0.0
#endif
#ifndef SERVO_ROLL_D
2012-08-21 23:19:51 -03:00
# define SERVO_ROLL_D 0.0
#endif
#ifndef SERVO_ROLL_INT_MAX
2012-08-21 23:19:51 -03:00
# define SERVO_ROLL_INT_MAX 5
#endif
#define SERVO_ROLL_INT_MAX_CENTIDEGREE SERVO_ROLL_INT_MAX*100
#ifndef ROLL_SLEW_LIMIT
2012-08-21 23:19:51 -03:00
# define ROLL_SLEW_LIMIT 0
#endif
#ifndef SERVO_PITCH_P
2012-08-21 23:19:51 -03:00
# define SERVO_PITCH_P 0.6
#endif
#ifndef SERVO_PITCH_I
2012-08-21 23:19:51 -03:00
# define SERVO_PITCH_I 0.0
#endif
#ifndef SERVO_PITCH_D
2012-08-21 23:19:51 -03:00
# define SERVO_PITCH_D 0.0
#endif
#ifndef SERVO_PITCH_INT_MAX
2012-08-21 23:19:51 -03:00
# define SERVO_PITCH_INT_MAX 5
#endif
#define SERVO_PITCH_INT_MAX_CENTIDEGREE SERVO_PITCH_INT_MAX*100
#ifndef PITCH_COMP
2012-08-21 23:19:51 -03:00
# define PITCH_COMP 0.2
#endif
#ifndef SERVO_YAW_P
2012-08-21 23:19:51 -03:00
# define SERVO_YAW_P 0.0
#endif
#ifndef SERVO_YAW_I
2012-08-21 23:19:51 -03:00
# define SERVO_YAW_I 0.0
#endif
#ifndef SERVO_YAW_D
2012-08-21 23:19:51 -03:00
# define SERVO_YAW_D 0.0
#endif
#ifndef SERVO_YAW_INT_MAX
2012-08-21 23:19:51 -03:00
# define SERVO_YAW_INT_MAX 0
#endif
#ifndef RUDDER_MIX
2012-08-21 23:19:51 -03:00
# define RUDDER_MIX 0.5
#endif
//////////////////////////////////////////////////////////////////////////////
// Navigation control gains
//
#ifndef NAV_ROLL_P
2012-08-21 23:19:51 -03:00
# define NAV_ROLL_P 0.7
#endif
#ifndef NAV_ROLL_I
2012-08-21 23:19:51 -03:00
# define NAV_ROLL_I 0.02
#endif
#ifndef NAV_ROLL_D
2012-08-21 23:19:51 -03:00
# define NAV_ROLL_D 0.1
#endif
#ifndef NAV_ROLL_INT_MAX
2012-08-21 23:19:51 -03:00
# define NAV_ROLL_INT_MAX 5
#endif
#define NAV_ROLL_INT_MAX_CENTIDEGREE NAV_ROLL_INT_MAX*100
#ifndef NAV_PITCH_ASP_P
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ASP_P 0.65
#endif
#ifndef NAV_PITCH_ASP_I
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ASP_I 0.1
#endif
#ifndef NAV_PITCH_ASP_D
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ASP_D 0.0
#endif
#ifndef NAV_PITCH_ASP_INT_MAX
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ASP_INT_MAX 5
#endif
#define NAV_PITCH_ASP_INT_MAX_CMSEC NAV_PITCH_ASP_INT_MAX*100
#ifndef NAV_PITCH_ALT_P
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ALT_P 0.65
#endif
#ifndef NAV_PITCH_ALT_I
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ALT_I 0.1
#endif
#ifndef NAV_PITCH_ALT_D
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ALT_D 0.0
#endif
#ifndef NAV_PITCH_ALT_INT_MAX
2012-08-21 23:19:51 -03:00
# define NAV_PITCH_ALT_INT_MAX 5
#endif
#define NAV_PITCH_ALT_INT_MAX_CM NAV_PITCH_ALT_INT_MAX*100
//////////////////////////////////////////////////////////////////////////////
// Energy/Altitude control gains
//
#ifndef THROTTLE_TE_P
2012-08-21 23:19:51 -03:00
# define THROTTLE_TE_P 0.50
#endif
#ifndef THROTTLE_TE_I
2012-08-21 23:19:51 -03:00
# define THROTTLE_TE_I 0.0
#endif
#ifndef THROTTLE_TE_D
2012-08-21 23:19:51 -03:00
# define THROTTLE_TE_D 0.0
#endif
#ifndef THROTTLE_TE_INT_MAX
2012-08-21 23:19:51 -03:00
# define THROTTLE_TE_INT_MAX 20
#endif
#ifndef THROTTLE_SLEW_LIMIT
2012-08-21 23:19:51 -03:00
# define THROTTLE_SLEW_LIMIT 0
#endif
#ifndef P_TO_T
2012-08-21 23:19:51 -03:00
# define P_TO_T 0
#endif
#ifndef T_TO_P
2012-08-21 23:19:51 -03:00
# define T_TO_P 0
#endif
#ifndef PITCH_TARGET
2012-08-21 23:19:51 -03:00
# define PITCH_TARGET 0
#endif
//////////////////////////////////////////////////////////////////////////////
// Crosstrack compensation
//
#ifndef XTRACK_GAIN
2012-08-21 23:19:51 -03:00
# define XTRACK_GAIN 1 // deg/m
#endif
#ifndef XTRACK_ENTRY_ANGLE
2012-08-21 23:19:51 -03:00
# define XTRACK_ENTRY_ANGLE 30 // deg
#endif
# define XTRACK_GAIN_SCALED XTRACK_GAIN*100
# define XTRACK_ENTRY_ANGLE_CENTIDEGREE XTRACK_ENTRY_ANGLE*100
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// DEBUGGING
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//
#ifndef LOGGING_ENABLED
2012-08-21 23:19:51 -03:00
# define LOGGING_ENABLED ENABLED
#endif
#ifndef LOG_ATTITUDE_FAST
2012-08-21 23:19:51 -03:00
# define LOG_ATTITUDE_FAST DISABLED
#endif
#ifndef LOG_ATTITUDE_MED
2012-08-21 23:19:51 -03:00
# define LOG_ATTITUDE_MED ENABLED
#endif
#ifndef LOG_GPS
2012-08-21 23:19:51 -03:00
# define LOG_GPS ENABLED
#endif
#ifndef LOG_PM
2012-08-21 23:19:51 -03:00
# define LOG_PM ENABLED
#endif
#ifndef LOG_CTUN
2012-08-21 23:19:51 -03:00
# define LOG_CTUN DISABLED
#endif
#ifndef LOG_NTUN
2012-08-21 23:19:51 -03:00
# define LOG_NTUN DISABLED
#endif
#ifndef LOG_MODE
2012-08-21 23:19:51 -03:00
# define LOG_MODE ENABLED
#endif
#ifndef LOG_RAW
2012-08-21 23:19:51 -03:00
# define LOG_RAW DISABLED
#endif
#ifndef LOG_CMD
2012-08-21 23:19:51 -03:00
# define LOG_CMD ENABLED
#endif
#ifndef LOG_CUR
2012-08-21 23:19:51 -03:00
# define LOG_CUR DISABLED
#endif
// calculate the default log_bitmask
2012-08-21 23:19:51 -03:00
#define LOGBIT(_s) (LOG_ ## _s ? MASK_LOG_ ## _s : 0)
#define DEFAULT_LOG_BITMASK \
2012-08-21 23:19:51 -03:00
LOGBIT(ATTITUDE_FAST) | \
LOGBIT(ATTITUDE_MED) | \
LOGBIT(GPS) | \
LOGBIT(PM) | \
LOGBIT(CTUN) | \
LOGBIT(NTUN) | \
LOGBIT(MODE) | \
LOGBIT(RAW) | \
LOGBIT(CMD) | \
LOGBIT(CUR)
//////////////////////////////////////////////////////////////////////////////
// Navigation defaults
//
#ifndef WP_RADIUS_DEFAULT
2012-08-21 23:19:51 -03:00
# define WP_RADIUS_DEFAULT 30
#endif
#ifndef LOITER_RADIUS_DEFAULT
2012-08-21 23:19:51 -03:00
# define LOITER_RADIUS_DEFAULT 60
#endif
#ifndef ALT_HOLD_HOME
2012-08-21 23:19:51 -03:00
# define ALT_HOLD_HOME 100
#endif
#define ALT_HOLD_HOME_CM ALT_HOLD_HOME*100
#ifndef USE_CURRENT_ALT
2012-08-21 23:19:51 -03:00
# define USE_CURRENT_ALT FALSE
#endif
#ifndef INVERTED_FLIGHT_PWM
2012-08-21 23:19:51 -03:00
# define INVERTED_FLIGHT_PWM 1750
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//
#ifndef SCALING_SPEED
2012-08-21 23:19:51 -03:00
# define SCALING_SPEED 15.0
#endif
// use this to enable servos in HIL mode
#ifndef HIL_SERVOS
2012-08-21 23:19:51 -03:00
# define HIL_SERVOS DISABLED
#endif
// use this to completely disable the CLI
#ifndef CLI_ENABLED
2012-08-21 23:19:51 -03:00
# define CLI_ENABLED ENABLED
#endif
// delay to prevent Xbee bricking, in milliseconds
#ifndef MAVLINK_TELEMETRY_PORT_DELAY
2012-08-21 23:19:51 -03:00
# define MAVLINK_TELEMETRY_PORT_DELAY 2000
#endif
// use this to disable gen-fencing
#ifndef GEOFENCE_ENABLED
2012-08-21 23:19:51 -03:00
# define GEOFENCE_ENABLED ENABLED
#endif
// pwm value on FENCE_CHANNEL to use to enable fenced mode
#ifndef FENCE_ENABLE_PWM
2012-08-21 23:19:51 -03:00
# define FENCE_ENABLE_PWM 1750
#endif
// a digital pin to set high when the geo-fence triggers. Defaults
// to -1, which means don't activate a pin
#ifndef FENCE_TRIGGERED_PIN
2012-08-21 23:19:51 -03:00
# define FENCE_TRIGGERED_PIN -1
#endif
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
// that channel where we reset the control mode to the current switch
// position (to for example return to switched mode after failsafe or
// fence breach)
#ifndef RESET_SWITCH_CHAN_PWM
2012-08-21 23:19:51 -03:00
# define RESET_SWITCH_CHAN_PWM 1750
#endif
// OBC Failsafe enable
#ifndef OBC_FAILSAFE
2012-08-21 23:19:51 -03:00
# define OBC_FAILSAFE DISABLED
#endif