2011-03-19 07:20:11 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2010-12-19 12:40:33 -04:00
|
|
|
//
|
2012-01-01 15:44:51 -04:00
|
|
|
#ifndef __ARDUCOPTER_CONFIG_H__
|
|
|
|
#define __ARDUCOPTER_CONFIG_H__
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//
|
|
|
|
// 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.
|
2011-02-19 22:03:01 -04:00
|
|
|
///
|
2012-04-18 16:16:02 -03:00
|
|
|
#ifdef USE_CMAKE_APM_CONFIG
|
|
|
|
#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists
|
|
|
|
#else
|
2011-02-24 01:56:59 -04:00
|
|
|
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
2012-04-18 16:16:02 -03:00
|
|
|
#endif
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// HARDWARE CONFIGURATION AND CONNECTIONS
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
2011-11-12 23:39:41 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// APM HARDWARE
|
|
|
|
//
|
|
|
|
|
|
|
|
#ifndef CONFIG_APM_HARDWARE
|
|
|
|
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
|
|
|
|
#endif
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
2011-11-25 19:11:25 -04:00
|
|
|
// APM2 HARDWARE DEFAULTS
|
2011-11-12 23:39:41 -04:00
|
|
|
//
|
|
|
|
|
2011-11-25 19:11:25 -04:00
|
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
2011-11-12 23:39:41 -04:00
|
|
|
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
|
|
|
|
# define CONFIG_PUSHBUTTON DISABLED
|
|
|
|
# define CONFIG_RELAY DISABLED
|
2011-11-13 18:45:15 -04:00
|
|
|
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
|
2011-11-12 23:39:41 -04:00
|
|
|
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
2011-12-28 05:30:35 -04:00
|
|
|
# define MAGNETOMETER ENABLED
|
2011-11-27 02:09:14 -04:00
|
|
|
# ifdef APM2_BETA_HARDWARE
|
|
|
|
# define CONFIG_BARO AP_BARO_BMP085
|
|
|
|
# else // APM2 Production Hardware (default)
|
2011-11-27 02:07:00 -04:00
|
|
|
# define CONFIG_BARO AP_BARO_MS5611
|
2011-11-27 02:09:14 -04:00
|
|
|
# endif
|
2011-11-12 23:39:41 -04:00
|
|
|
#endif
|
|
|
|
|
2012-06-03 21:02:08 -03:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// MAVLINK10
|
|
|
|
//
|
|
|
|
#ifndef MAVLINK10
|
|
|
|
# define MAVLINK10 ENABLED
|
|
|
|
#endif
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// FRAME_CONFIG
|
2011-02-19 22:03:01 -04:00
|
|
|
//
|
2010-12-19 12:40:33 -04:00
|
|
|
#ifndef FRAME_CONFIG
|
2012-01-08 02:23:44 -04:00
|
|
|
# define FRAME_CONFIG QUAD_FRAME
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-05-18 20:38:24 -03:00
|
|
|
#ifndef FRAME_ORIENTATION
|
2012-01-08 02:23:44 -04:00
|
|
|
# define FRAME_ORIENTATION X_FRAME
|
2011-05-18 20:38:24 -03:00
|
|
|
#endif
|
|
|
|
|
2011-11-12 23:39:41 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// IMU Selection
|
|
|
|
//
|
|
|
|
#ifndef CONFIG_IMU_TYPE
|
|
|
|
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
|
|
|
|
# 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
|
|
|
|
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
|
|
|
|
# define CONFIG_ADC ENABLED
|
|
|
|
# else
|
|
|
|
# define CONFIG_ADC DISABLED
|
|
|
|
# endif
|
|
|
|
#endif
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-10-12 02:20:23 -03:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// PWM control
|
|
|
|
//
|
|
|
|
#ifndef INSTANT_PWM
|
|
|
|
# define INSTANT_PWM DISABLED
|
|
|
|
#endif
|
|
|
|
|
2012-03-02 02:24:44 -04:00
|
|
|
// default RC speed in Hz if INSTANT_PWM is not used
|
|
|
|
#ifndef RC_FAST_SPEED
|
2012-04-21 11:46:36 -03:00
|
|
|
# if FRAME_CONFIG == HELI_FRAME
|
|
|
|
# define RC_FAST_SPEED 125
|
|
|
|
# else
|
|
|
|
# define RC_FAST_SPEED 490
|
|
|
|
# endif
|
2012-03-02 02:24:44 -04:00
|
|
|
#endif
|
|
|
|
|
2012-05-15 11:07:03 -03:00
|
|
|
////////////////////////////////////////////////////////
|
2011-11-12 23:39:41 -04:00
|
|
|
// LED and IO Pins
|
|
|
|
//
|
|
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
|
|
|
# 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
|
2011-11-20 05:42:51 -04:00
|
|
|
# define USB_MUX_PIN -1
|
2011-12-11 13:53:05 -04:00
|
|
|
# define CLI_SLIDER_ENABLED DISABLED
|
2011-12-29 23:06:31 -04:00
|
|
|
# define OPTFLOW_CS_PIN 34
|
2012-01-15 20:10:02 -04:00
|
|
|
# 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
|
2011-11-12 23:39:41 -04: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
|
2011-12-29 23:06:31 -04:00
|
|
|
# define USB_MUX_PIN 23
|
2012-04-21 08:15:16 -03:00
|
|
|
# define OPTFLOW_CS_PIN A3
|
2012-01-15 20:10:02 -04:00
|
|
|
# define BATTERY_PIN_1 1
|
|
|
|
# define CURRENT_PIN_1 2
|
2011-11-12 23:39:41 -04:00
|
|
|
#endif
|
|
|
|
|
2012-05-15 11:07:03 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// CopterLEDs
|
|
|
|
//
|
|
|
|
|
2012-04-12 10:51:17 -03:00
|
|
|
#ifndef COPTER_LEDS
|
|
|
|
#define COPTER_LEDS ENABLED
|
|
|
|
#endif
|
|
|
|
|
2012-05-15 11:07:03 -03:00
|
|
|
#define COPTER_LED_ON HIGH
|
|
|
|
#define COPTER_LED_OFF LOW
|
|
|
|
|
|
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
2012-05-15 13:00:21 -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
|
2012-05-15 11:07:03 -03:00
|
|
|
#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
|
|
|
|
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
2012-05-15 13:00:21 -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
|
2012-05-15 11:07:03 -03:00
|
|
|
#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
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2011-11-12 23:39:41 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Pushbutton & Relay
|
|
|
|
//
|
|
|
|
|
|
|
|
#ifndef CONFIG_PUSHBUTTON
|
|
|
|
# define CONFIG_PUSHBUTTON ENABLED
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef CONFIG_RELAY
|
|
|
|
# define CONFIG_RELAY ENABLED
|
|
|
|
#endif
|
2011-10-12 02:20:23 -03:00
|
|
|
|
2011-11-27 02:07:00 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Barometer
|
|
|
|
//
|
|
|
|
|
|
|
|
#ifndef CONFIG_BARO
|
|
|
|
# define CONFIG_BARO AP_BARO_BMP085
|
|
|
|
#endif
|
|
|
|
|
2011-02-20 19:09:28 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Sonar
|
|
|
|
//
|
2011-06-16 14:03:26 -03:00
|
|
|
|
2011-11-12 23:39:41 -04:00
|
|
|
#ifndef CONFIG_SONAR_SOURCE
|
|
|
|
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ADC
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC && CONFIG_ADC == DISABLED
|
|
|
|
# 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
|
|
|
|
# ifndef CONFIG_SONAR_SOURCE_ADC_CHANNEL
|
|
|
|
# define CONFIG_SONAR_SOURCE_ADC_CHANNEL 7
|
|
|
|
# endif
|
|
|
|
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
|
|
|
|
# ifndef CONFIG_SONAR_SOURCE_ANALOG_PIN
|
2012-01-26 09:50:48 -04:00
|
|
|
# define CONFIG_SONAR_SOURCE_ANALOG_PIN A0
|
2011-11-12 23:39:41 -04:00
|
|
|
# endif
|
|
|
|
#else
|
|
|
|
# warning Invalid value for CONFIG_SONAR_SOURCE, disabling sonar
|
|
|
|
# undef SONAR_ENABLED
|
|
|
|
# define SONAR_ENABLED DISABLED
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef CONFIG_SONAR
|
|
|
|
# define CONFIG_SONAR ENABLED
|
|
|
|
#endif
|
|
|
|
|
2012-02-11 19:53:09 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Channel Config (custom MOT channel mappings)
|
|
|
|
//
|
|
|
|
|
|
|
|
#ifndef CONFIG_CHANNELS
|
|
|
|
# define CONFIG_CHANNELS CHANNEL_CONFIG_DEFAULT
|
|
|
|
#endif
|
2011-11-12 23:39:41 -04:00
|
|
|
|
2011-08-05 13:21:21 -03:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Acrobatics
|
|
|
|
//
|
|
|
|
|
|
|
|
#ifndef CH7_OPTION
|
2012-02-10 02:33:01 -04:00
|
|
|
# define CH7_OPTION CH7_SAVE_WP
|
2011-08-05 13:21:21 -03:00
|
|
|
#endif
|
|
|
|
|
2011-05-25 02:48:33 -03:00
|
|
|
|
2011-02-24 01:56:59 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// HIL_MODE OPTIONAL
|
|
|
|
|
2011-05-09 09:20:22 -03:00
|
|
|
#ifndef HIL_MODE
|
|
|
|
#define HIL_MODE HIL_MODE_DISABLED
|
|
|
|
#endif
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2011-05-09 09:20:22 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
|
2011-05-09 12:46:56 -03:00
|
|
|
|
2011-05-09 09:20:22 -03:00
|
|
|
# undef GPS_PROTOCOL
|
|
|
|
# define GPS_PROTOCOL GPS_PROTOCOL_NONE
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2011-12-11 23:59:39 -04:00
|
|
|
#undef CONFIG_SONAR
|
|
|
|
#define CONFIG_SONAR DISABLED
|
2011-02-24 01:56:59 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// GPS_PROTOCOL
|
|
|
|
//
|
|
|
|
#ifndef GPS_PROTOCOL
|
2011-05-18 20:38:24 -03:00
|
|
|
# define GPS_PROTOCOL GPS_PROTOCOL_AUTO
|
2011-02-24 01:56:59 -04:00
|
|
|
#endif
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-05-25 02:48:33 -03:00
|
|
|
|
2011-05-09 12:46:56 -03:00
|
|
|
#ifndef MAV_SYSTEM_ID
|
|
|
|
# define MAV_SYSTEM_ID 1
|
|
|
|
#endif
|
|
|
|
|
2011-05-25 02:48:33 -03:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Serial port speeds.
|
|
|
|
//
|
|
|
|
#ifndef SERIAL0_BAUD
|
2011-02-24 01:56:59 -04:00
|
|
|
# define SERIAL0_BAUD 115200
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef SERIAL3_BAUD
|
2011-02-24 01:56:59 -04:00
|
|
|
# define SERIAL3_BAUD 57600
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Battery monitoring
|
|
|
|
//
|
|
|
|
#ifndef BATTERY_EVENT
|
|
|
|
# define BATTERY_EVENT DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOW_VOLTAGE
|
2011-01-16 23:44:12 -04:00
|
|
|
# define LOW_VOLTAGE 9.6
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef VOLT_DIV_RATIO
|
2011-05-09 12:46:56 -03:00
|
|
|
# define VOLT_DIV_RATIO 3.56
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2011-05-09 12:46:56 -03:00
|
|
|
#ifndef CURR_AMP_PER_VOLT
|
|
|
|
# define CURR_AMP_PER_VOLT 27.32
|
2011-01-16 23:44:12 -04:00
|
|
|
#endif
|
2011-05-09 12:46:56 -03:00
|
|
|
#ifndef CURR_AMPS_OFFSET
|
|
|
|
# define CURR_AMPS_OFFSET 0.0
|
2011-01-16 23:44:12 -04:00
|
|
|
#endif
|
2011-05-09 12:46:56 -03:00
|
|
|
#ifndef HIGH_DISCHARGE
|
2011-09-18 21:12:28 -03:00
|
|
|
# define HIGH_DISCHARGE 1760
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2012-05-15 11:07:03 -03:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-05-25 02:48:33 -03:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// INPUT_VOLTAGE
|
|
|
|
//
|
|
|
|
#ifndef INPUT_VOLTAGE
|
|
|
|
# define INPUT_VOLTAGE 5.0
|
|
|
|
#endif
|
|
|
|
|
2011-05-25 02:48:33 -03:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// MAGNETOMETER
|
2011-02-24 01:56:59 -04:00
|
|
|
#ifndef MAGNETOMETER
|
2011-12-26 20:00:39 -04:00
|
|
|
# define MAGNETOMETER ENABLED
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-02-24 01:56:59 -04:00
|
|
|
#ifndef MAG_ORIENTATION
|
|
|
|
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2011-10-15 20:34:57 -03:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// CAMERA GAINS
|
|
|
|
#ifndef CAM_ROLL_GAIN
|
|
|
|
# define CAM_ROLL_GAIN 1.0
|
|
|
|
#endif
|
|
|
|
#ifndef CAM_PITCH_GAIN
|
|
|
|
# define CAM_PITCH_GAIN 1.0
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
2011-07-21 20:14:53 -03:00
|
|
|
// OPTICAL_FLOW
|
|
|
|
#if defined( __AVR_ATmega2560__ ) // determines if optical flow code is included
|
2011-12-10 10:22:40 -04:00
|
|
|
#define OPTFLOW_ENABLED
|
2011-07-21 20:14:53 -03:00
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW // sets global enabled/disabled flag for optflow (as seen in CLI)
|
|
|
|
# define OPTFLOW DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW_ORIENTATION
|
|
|
|
# define OPTFLOW_ORIENTATION AP_OPTICALFLOW_ADNS3080_PINS_FORWARD
|
|
|
|
#endif
|
2012-01-25 08:55:14 -04:00
|
|
|
#ifndef OPTFLOW_RESOLUTION
|
|
|
|
# define OPTFLOW_RESOLUTION ADNS3080_RESOLUTION_1600
|
|
|
|
#endif
|
2011-07-21 20:14:53 -03:00
|
|
|
#ifndef OPTFLOW_FOV
|
2011-08-07 10:15:19 -03:00
|
|
|
# define OPTFLOW_FOV AP_OPTICALFLOW_ADNS3080_08_FOV
|
2011-07-21 20:14:53 -03:00
|
|
|
#endif
|
2012-01-09 00:53:54 -04:00
|
|
|
// optical flow based loiter PI values
|
|
|
|
#ifndef OPTFLOW_ROLL_P
|
2012-01-25 08:55:14 -04:00
|
|
|
#define OPTFLOW_ROLL_P 2.5
|
2012-01-09 00:53:54 -04:00
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW_ROLL_I
|
2012-01-31 19:04:18 -04:00
|
|
|
#define OPTFLOW_ROLL_I 3.2
|
2012-01-25 08:55:14 -04:00
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW_ROLL_D
|
|
|
|
#define OPTFLOW_ROLL_D 0.12
|
2012-01-09 00:53:54 -04:00
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW_PITCH_P
|
2012-01-25 08:55:14 -04:00
|
|
|
#define OPTFLOW_PITCH_P 2.5
|
2012-01-09 00:53:54 -04:00
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW_PITCH_I
|
2012-01-31 19:04:18 -04:00
|
|
|
#define OPTFLOW_PITCH_I 3.2
|
2012-01-25 08:55:14 -04:00
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW_PITCH_D
|
|
|
|
#define OPTFLOW_PITCH_D 0.12
|
2012-01-09 00:53:54 -04:00
|
|
|
#endif
|
|
|
|
#ifndef OPTFLOW_IMAX
|
|
|
|
#define OPTFLOW_IMAX 4
|
|
|
|
#endif
|
|
|
|
|
2011-07-21 20:14:53 -03:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// RADIO CONFIGURATION
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// FLIGHT_MODE
|
|
|
|
//
|
|
|
|
|
|
|
|
#if !defined(FLIGHT_MODE_1)
|
|
|
|
# define FLIGHT_MODE_1 STABILIZE
|
|
|
|
#endif
|
|
|
|
#if !defined(FLIGHT_MODE_2)
|
|
|
|
# define FLIGHT_MODE_2 STABILIZE
|
|
|
|
#endif
|
|
|
|
#if !defined(FLIGHT_MODE_3)
|
|
|
|
# define FLIGHT_MODE_3 STABILIZE
|
|
|
|
#endif
|
|
|
|
#if !defined(FLIGHT_MODE_4)
|
|
|
|
# define FLIGHT_MODE_4 STABILIZE
|
|
|
|
#endif
|
|
|
|
#if !defined(FLIGHT_MODE_5)
|
|
|
|
# define FLIGHT_MODE_5 STABILIZE
|
|
|
|
#endif
|
|
|
|
#if !defined(FLIGHT_MODE_6)
|
|
|
|
# define FLIGHT_MODE_6 STABILIZE
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// THROTTLE_FAILSAFE
|
|
|
|
// THROTTLE_FS_VALUE
|
|
|
|
// THROTTLE_FAILSAFE_ACTION
|
|
|
|
//
|
|
|
|
#ifndef THROTTLE_FAILSAFE
|
2011-05-21 03:50:46 -03:00
|
|
|
# define THROTTLE_FAILSAFE DISABLED
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef THROTTE_FS_VALUE
|
2011-05-21 03:50:46 -03:00
|
|
|
# define THROTTLE_FS_VALUE 975
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef THROTTLE_FAILSAFE_ACTION
|
2011-05-21 03:50:46 -03:00
|
|
|
# define THROTTLE_FAILSAFE_ACTION 2
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-06-19 02:31:33 -03:00
|
|
|
#ifndef MINIMUM_THROTTLE
|
2012-06-20 19:22:24 -03:00
|
|
|
# define MINIMUM_THROTTLE 130
|
2011-06-19 02:31:33 -03:00
|
|
|
#endif
|
2011-12-29 02:37:00 -04:00
|
|
|
#ifndef MAXIMUM_THROTTLE
|
2012-06-12 17:57:31 -03:00
|
|
|
# define MAXIMUM_THROTTLE 1000
|
2011-12-29 02:37:00 -04:00
|
|
|
#endif
|
|
|
|
|
2012-01-20 20:48:47 -04:00
|
|
|
#ifndef AUTO_LAND_TIME
|
|
|
|
# define AUTO_LAND_TIME 20
|
|
|
|
#endif
|
|
|
|
|
2011-12-29 02:37:00 -04:00
|
|
|
|
2011-06-19 02:31:33 -03:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// STARTUP BEHAVIOUR
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// GROUND_START_DELAY
|
|
|
|
//
|
|
|
|
#ifndef GROUND_START_DELAY
|
2011-06-01 02:50:17 -03:00
|
|
|
# define GROUND_START_DELAY 3
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// FLIGHT AND NAVIGATION CONTROL
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
2011-04-17 02:17:42 -03:00
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Y6 Support
|
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef TOP_BOTTOM_RATIO
|
2011-11-07 02:43:49 -04:00
|
|
|
# define TOP_BOTTOM_RATIO 1.00
|
2011-04-17 02:17:42 -03:00
|
|
|
#endif
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-09-04 21:15:36 -03:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Attitude Control
|
|
|
|
//
|
|
|
|
|
|
|
|
// Alt Hold Mode
|
|
|
|
#ifndef ALT_HOLD_YAW
|
|
|
|
# define ALT_HOLD_YAW YAW_HOLD
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef ALT_HOLD_RP
|
|
|
|
# define ALT_HOLD_RP ROLL_PITCH_STABLE
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef ALT_HOLD_THR
|
|
|
|
# define ALT_HOLD_THR THROTTLE_HOLD
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// AUTO Mode
|
|
|
|
#ifndef AUTO_YAW
|
|
|
|
# define AUTO_YAW YAW_AUTO
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef AUTO_RP
|
|
|
|
# define AUTO_RP ROLL_PITCH_AUTO
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef AUTO_THR
|
|
|
|
# define AUTO_THR THROTTLE_AUTO
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// CIRCLE Mode
|
|
|
|
#ifndef CIRCLE_YAW
|
2011-09-11 15:48:11 -03:00
|
|
|
# define CIRCLE_YAW YAW_AUTO
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef CIRCLE_RP
|
|
|
|
# define CIRCLE_RP ROLL_PITCH_AUTO
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef CIRCLE_THR
|
|
|
|
# define CIRCLE_THR THROTTLE_HOLD
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// LOITER Mode
|
|
|
|
#ifndef LOITER_YAW
|
|
|
|
# define LOITER_YAW YAW_HOLD
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef LOITER_RP
|
|
|
|
# define LOITER_RP ROLL_PITCH_AUTO
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef LOITER_THR
|
|
|
|
# define LOITER_THR THROTTLE_HOLD
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
// RTL Mode
|
|
|
|
#ifndef RTL_YAW
|
2011-11-20 16:50:06 -04:00
|
|
|
# define RTL_YAW YAW_HOLD
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef RTL_RP
|
|
|
|
# define RTL_RP ROLL_PITCH_AUTO
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef RTL_THR
|
2011-09-22 16:28:46 -03:00
|
|
|
# define RTL_THR THROTTLE_HOLD
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
|
|
|
|
2011-12-16 00:47:57 -04:00
|
|
|
#ifndef SUPER_SIMPLE
|
|
|
|
# define SUPER_SIMPLE DISABLED
|
2011-12-12 14:20:15 -04:00
|
|
|
#endif
|
|
|
|
|
2012-06-26 14:38:33 -03:00
|
|
|
#ifndef SUPER_SIMPLE_RADIUS
|
|
|
|
# define SUPER_SIMPLE_RADIUS 1000
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2012-02-15 13:09:42 -04:00
|
|
|
// RTL Mode
|
|
|
|
#ifndef RTL_AUTO_LAND
|
|
|
|
# define RTL_AUTO_LAND ENABLED
|
|
|
|
#endif
|
|
|
|
|
2012-01-27 20:27:16 -04:00
|
|
|
// LOITER Mode
|
|
|
|
#ifndef OF_LOITER_YAW
|
|
|
|
# define OF_LOITER_YAW YAW_HOLD
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef OF_LOITER_RP
|
|
|
|
# define OF_LOITER_RP ROLL_PITCH_STABLE_OF
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef OF_LOITER_THR
|
|
|
|
# define OF_LOITER_THR THROTTLE_HOLD
|
|
|
|
#endif
|
2011-09-04 21:15:36 -03:00
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
2011-07-31 17:09:27 -03:00
|
|
|
// Attitude Control
|
2011-07-10 21:47:08 -03:00
|
|
|
//
|
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-01-30 22:00:31 -04:00
|
|
|
# define STABILIZE_ROLL_P 3.7
|
2011-12-18 22:29:05 -04:00
|
|
|
# define STABILIZE_ROLL_I 0.0
|
2012-02-11 02:25:01 -04:00
|
|
|
# define STABILIZE_ROLL_IMAX 40.0 // degrees
|
2012-01-30 22:00:31 -04:00
|
|
|
# define STABILIZE_PITCH_P 3.7
|
2011-12-18 22:29:05 -04:00
|
|
|
# define STABILIZE_PITCH_I 0.0
|
2012-02-11 02:25:01 -04:00
|
|
|
# define STABILIZE_PITCH_IMAX 40.0 // degrees
|
2011-10-21 00:41:52 -03:00
|
|
|
#endif
|
|
|
|
|
2011-12-18 22:29:05 -04:00
|
|
|
#ifdef MOTORS_JD850
|
2012-01-30 22:00:31 -04:00
|
|
|
# define STABILIZE_ROLL_P 4.2
|
2011-12-18 22:29:05 -04:00
|
|
|
# define STABILIZE_ROLL_I 0.0
|
2012-02-11 02:25:01 -04:00
|
|
|
# define STABILIZE_ROLL_IMAX 40.0 // degrees
|
2012-01-30 22:00:31 -04:00
|
|
|
# define STABILIZE_PITCH_P 4.2
|
2011-12-18 22:29:05 -04:00
|
|
|
# define STABILIZE_PITCH_I 0.0
|
2012-02-11 02:25:01 -04:00
|
|
|
# define STABILIZE_PITCH_IMAX 40.0 // degrees
|
2011-12-18 22:29:05 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2012-02-18 18:23:21 -04:00
|
|
|
#ifndef ACRO_P
|
|
|
|
# define ACRO_P 4.5
|
2011-12-29 14:23:59 -04:00
|
|
|
#endif
|
|
|
|
|
2012-02-15 15:29:25 -04:00
|
|
|
|
2012-02-18 18:23:21 -04:00
|
|
|
#ifndef AXIS_LOCK_ENABLED
|
|
|
|
# define AXIS_LOCK_ENABLED DISABLED
|
|
|
|
#endif
|
2012-02-15 15:29:25 -04:00
|
|
|
|
2012-02-18 18:23:21 -04:00
|
|
|
#ifndef AXIS_LOCK_P
|
|
|
|
# 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.
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef STABILIZE_ROLL_P
|
2012-02-18 18:23:21 -04:00
|
|
|
# define STABILIZE_ROLL_P 4.5
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef STABILIZE_ROLL_I
|
2012-06-30 07:26:14 -03:00
|
|
|
# define STABILIZE_ROLL_I 0.01
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef STABILIZE_ROLL_IMAX
|
2011-12-03 19:38:46 -04:00
|
|
|
# define STABILIZE_ROLL_IMAX 40 // degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
2011-07-31 17:09:27 -03:00
|
|
|
#ifndef STABILIZE_PITCH_P
|
2012-02-18 18:23:21 -04:00
|
|
|
# define STABILIZE_PITCH_P 4.5
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-31 17:09:27 -03:00
|
|
|
#ifndef STABILIZE_PITCH_I
|
2012-03-07 02:12:24 -04:00
|
|
|
# define STABILIZE_PITCH_I 0.1
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-31 17:09:27 -03:00
|
|
|
#ifndef STABILIZE_PITCH_IMAX
|
2011-12-03 19:38:46 -04:00
|
|
|
# define STABILIZE_PITCH_IMAX 40 // degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
2012-01-29 02:00:05 -04:00
|
|
|
#ifndef STABILIZE_YAW_P
|
2012-02-17 02:19:39 -04: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
|
2012-01-29 02:00:05 -04:00
|
|
|
#ifndef STABILIZE_YAW_I
|
|
|
|
# define STABILIZE_YAW_I 0.01
|
2011-10-27 15:55:13 -03:00
|
|
|
#endif
|
2012-01-29 02:00:05 -04:00
|
|
|
#ifndef STABILIZE_YAW_IMAX
|
|
|
|
# define STABILIZE_YAW_IMAX 8 // degrees * 100
|
2011-10-27 15:55:13 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Stabilize Rate Control
|
2010-12-19 12:40:33 -04:00
|
|
|
//
|
2011-07-31 17:09:27 -03:00
|
|
|
#ifndef RATE_ROLL_P
|
2012-06-05 20:41:31 -03:00
|
|
|
# define RATE_ROLL_P 0.18
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-31 17:09:27 -03:00
|
|
|
#ifndef RATE_ROLL_I
|
2012-02-18 18:23:21 -04:00
|
|
|
# define RATE_ROLL_I 0.0
|
2012-01-29 02:00:05 -04:00
|
|
|
#endif
|
|
|
|
#ifndef RATE_ROLL_D
|
2012-06-05 20:41:31 -03:00
|
|
|
# define RATE_ROLL_D 0.004
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-31 17:09:27 -03:00
|
|
|
#ifndef RATE_ROLL_IMAX
|
2012-02-11 19:27:50 -04:00
|
|
|
# define RATE_ROLL_IMAX 5 // degrees
|
2011-07-10 21:47:08 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef RATE_PITCH_P
|
2012-06-05 20:41:31 -03:00
|
|
|
# define RATE_PITCH_P 0.18
|
2011-07-10 21:47:08 -03:00
|
|
|
#endif
|
|
|
|
#ifndef RATE_PITCH_I
|
2012-02-18 18:23:21 -04:00
|
|
|
# define RATE_PITCH_I 0.0
|
2012-01-29 02:00:05 -04:00
|
|
|
#endif
|
|
|
|
#ifndef RATE_PITCH_D
|
2012-06-05 20:41:31 -03:00
|
|
|
# define RATE_PITCH_D 0.004
|
2011-07-10 21:47:08 -03:00
|
|
|
#endif
|
|
|
|
#ifndef RATE_PITCH_IMAX
|
2012-02-11 19:27:50 -04:00
|
|
|
# define RATE_PITCH_IMAX 5 // degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef RATE_YAW_P
|
2012-01-29 02:00:05 -04:00
|
|
|
# define RATE_YAW_P .13
|
2011-07-10 21:47:08 -03:00
|
|
|
#endif
|
|
|
|
#ifndef RATE_YAW_I
|
2012-01-29 02:00:05 -04:00
|
|
|
# define RATE_YAW_I 0.0
|
|
|
|
#endif
|
|
|
|
#ifndef RATE_YAW_D
|
2012-03-07 02:12:24 -04:00
|
|
|
# define RATE_YAW_D 0.000
|
2011-07-10 21:47:08 -03:00
|
|
|
#endif
|
|
|
|
#ifndef RATE_YAW_IMAX
|
2012-01-29 02:00:05 -04:00
|
|
|
# define RATE_YAW_IMAX 50 // degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-06-30 21:19:10 -03:00
|
|
|
|
|
|
|
|
2012-02-18 18:23:21 -04:00
|
|
|
#ifndef STABILIZE_D
|
2012-06-05 20:41:31 -03:00
|
|
|
# define STABILIZE_D 0.00
|
2012-02-29 00:15:18 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef STABILIZE_D_SCHEDULE
|
2012-03-07 02:12:24 -04:00
|
|
|
# define STABILIZE_D_SCHEDULE 0.5
|
2012-02-18 18:23:21 -04:00
|
|
|
#endif
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
2012-01-12 01:49:23 -04:00
|
|
|
// Loiter control gains
|
2010-12-19 12:40:33 -04:00
|
|
|
//
|
2011-09-04 21:15:36 -03:00
|
|
|
#ifndef LOITER_P
|
2012-06-12 08:56:31 -03:00
|
|
|
# define LOITER_P .20
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-09-04 21:15:36 -03:00
|
|
|
#ifndef LOITER_I
|
2012-01-31 01:12:42 -04:00
|
|
|
# define LOITER_I 0.0
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-09-04 21:15:36 -03:00
|
|
|
#ifndef LOITER_IMAX
|
2012-01-29 02:00:05 -04:00
|
|
|
# define LOITER_IMAX 30 // degrees
|
2012-01-22 02:09:13 -04:00
|
|
|
#endif
|
2011-04-25 02:12:59 -03:00
|
|
|
|
2012-02-15 13:09:42 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Loiter Navigation control gains
|
|
|
|
//
|
|
|
|
#ifndef LOITER_RATE_P
|
2012-06-12 08:56:31 -03:00
|
|
|
# define LOITER_RATE_P 2.4 //
|
2012-02-15 13:09:42 -04:00
|
|
|
#endif
|
|
|
|
#ifndef LOITER_RATE_I
|
2012-05-16 02:01:01 -03:00
|
|
|
# define LOITER_RATE_I 0.08 // Wind control
|
2012-02-15 13:09:42 -04:00
|
|
|
#endif
|
|
|
|
#ifndef LOITER_RATE_D
|
2012-06-12 08:56:31 -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-02-24 02:02:23 -04:00
|
|
|
# define LOITER_RATE_IMAX 30 // degrees
|
2012-02-15 13:09:42 -04:00
|
|
|
#endif
|
|
|
|
|
2012-01-12 01:49:23 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// WP Navigation control gains
|
|
|
|
//
|
2011-09-04 21:15:36 -03:00
|
|
|
#ifndef NAV_P
|
2012-06-29 18:36:13 -03:00
|
|
|
# define NAV_P 2.4 //
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
|
|
|
#ifndef NAV_I
|
2012-06-29 18:36:13 -03:00
|
|
|
# define NAV_I 0.17 // Wind control
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
2012-01-29 02:00:05 -04:00
|
|
|
#ifndef NAV_D
|
2012-01-31 01:12:42 -04:00
|
|
|
# define NAV_D 0.00 //
|
2012-01-29 02:00:05 -04:00
|
|
|
#endif
|
2011-09-04 21:15:36 -03:00
|
|
|
#ifndef NAV_IMAX
|
2012-06-19 23:53:29 -03:00
|
|
|
# define NAV_IMAX 18 // degrees
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
2011-06-28 03:31:18 -03:00
|
|
|
|
2012-02-15 13:09:42 -04:00
|
|
|
#ifndef AUTO_SLEW_RATE
|
|
|
|
# define AUTO_SLEW_RATE 30 // degrees
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef WAYPOINT_SPEED_MAX
|
2012-01-29 02:00:05 -04:00
|
|
|
# define WAYPOINT_SPEED_MAX 600 // 6m/s error = 13mph
|
2011-06-28 03:31:18 -03:00
|
|
|
#endif
|
|
|
|
|
2012-01-22 02:09:13 -04:00
|
|
|
#ifndef WAYPOINT_SPEED_MIN
|
2012-01-29 02:00:05 -04:00
|
|
|
# define WAYPOINT_SPEED_MIN 100 // 1m/s
|
2012-01-22 02:09:13 -04:00
|
|
|
#endif
|
|
|
|
|
2011-09-04 21:15:36 -03:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Throttle control gains
|
|
|
|
//
|
2012-03-22 14:01:24 -03:00
|
|
|
#ifndef AUTO_THROTTLE_HOLD
|
|
|
|
# define AUTO_THROTTLE_HOLD 1
|
|
|
|
#endif
|
|
|
|
|
2011-09-23 03:10:55 -03:00
|
|
|
#ifndef THROTTLE_CRUISE
|
2012-03-20 04:34:07 -03:00
|
|
|
# define THROTTLE_CRUISE 450 //
|
2011-09-23 03:10:55 -03:00
|
|
|
#endif
|
|
|
|
|
2012-01-29 02:00:05 -04:00
|
|
|
#ifndef ALT_HOLD_P
|
2012-06-26 02:21:43 -03:00
|
|
|
# define ALT_HOLD_P 0.8 // .5
|
2011-10-02 15:36:23 -03:00
|
|
|
#endif
|
2012-01-29 02:00:05 -04:00
|
|
|
#ifndef ALT_HOLD_I
|
2012-05-29 16:43:01 -03:00
|
|
|
# define ALT_HOLD_I 0.007
|
2011-10-02 15:36:23 -03:00
|
|
|
#endif
|
2012-01-29 02:00:05 -04:00
|
|
|
#ifndef ALT_HOLD_IMAX
|
|
|
|
# define ALT_HOLD_IMAX 300
|
2011-10-02 15:36:23 -03:00
|
|
|
#endif
|
|
|
|
|
2011-10-16 19:41:54 -03:00
|
|
|
// RATE control
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef THROTTLE_P
|
2012-06-26 02:21:43 -03:00
|
|
|
# define THROTTLE_P 0.35 // .25
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef THROTTLE_I
|
2012-03-07 02:22:14 -04:00
|
|
|
# define THROTTLE_I 0.0 // Don't edit
|
2012-01-29 02:00:05 -04:00
|
|
|
#endif
|
|
|
|
#ifndef THROTTLE_D
|
|
|
|
# define THROTTLE_D 0.02 //
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-07-10 21:47:08 -03:00
|
|
|
#ifndef THROTTLE_IMAX
|
2012-01-29 02:00:05 -04:00
|
|
|
# define THROTTLE_IMAX 300
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Crosstrack compensation
|
|
|
|
//
|
2011-11-19 17:59:15 -04:00
|
|
|
#ifndef CROSSTRACK_GAIN
|
2012-06-26 02:21:43 -03:00
|
|
|
# define CROSSTRACK_GAIN .2
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// DEBUGGING
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// DEBUG_LEVEL
|
|
|
|
//
|
|
|
|
#ifndef DEBUG_LEVEL
|
|
|
|
# define DEBUG_LEVEL SEVERITY_LOW
|
|
|
|
#endif
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Dataflash logging control
|
|
|
|
//
|
2011-12-23 22:44:30 -04:00
|
|
|
// Logging must be disabled for 1280 build.
|
2011-12-09 19:01:14 -04:00
|
|
|
#if defined( __AVR_ATmega1280__ )
|
2011-12-23 22:44:30 -04:00
|
|
|
# if LOGGING_ENABLED == ENABLED
|
|
|
|
// If logging was enabled in APM_Config or command line, warn the user.
|
|
|
|
# warning "Logging is not supported on ATmega1280"
|
|
|
|
# undef LOGGING_ENABLED
|
2011-12-09 19:01:14 -04:00
|
|
|
# endif
|
2011-12-23 22:44:30 -04:00
|
|
|
# ifndef LOGGING_ENABLED
|
|
|
|
# define LOGGING_ENABLED DISABLED
|
|
|
|
# endif
|
|
|
|
#elif !defined(LOGGING_ENABLED)
|
|
|
|
// Logging is enabled by default for all other builds.
|
|
|
|
# define LOGGING_ENABLED ENABLED
|
2011-07-17 07:31:07 -03:00
|
|
|
#endif
|
|
|
|
|
2011-12-03 19:38:46 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
#ifndef LOG_ATTITUDE_FAST
|
|
|
|
# define LOG_ATTITUDE_FAST DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_ATTITUDE_MED
|
2011-09-14 17:58:18 -03:00
|
|
|
# define LOG_ATTITUDE_MED ENABLED
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef LOG_GPS
|
|
|
|
# define LOG_GPS ENABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_PM
|
|
|
|
# define LOG_PM ENABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_CTUN
|
2011-06-28 03:31:18 -03:00
|
|
|
# define LOG_CTUN ENABLED
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef LOG_NTUN
|
2011-06-28 03:31:18 -03:00
|
|
|
# define LOG_NTUN ENABLED
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef LOG_MODE
|
|
|
|
# define LOG_MODE ENABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_RAW
|
|
|
|
# define LOG_RAW DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_CMD
|
|
|
|
# define LOG_CMD ENABLED
|
|
|
|
#endif
|
2011-07-30 17:42:54 -03:00
|
|
|
// current
|
|
|
|
#ifndef LOG_CUR
|
|
|
|
# define LOG_CUR DISABLED
|
|
|
|
#endif
|
|
|
|
// quad motor PWMs
|
|
|
|
#ifndef LOG_MOTORS
|
|
|
|
# define LOG_MOTORS DISABLED
|
|
|
|
#endif
|
2012-03-25 03:55:49 -03:00
|
|
|
// optical flow
|
2011-07-30 17:42:54 -03:00
|
|
|
#ifndef LOG_OPTFLOW
|
2012-01-31 01:12:42 -04:00
|
|
|
# define LOG_OPTFLOW DISABLED
|
2011-01-16 23:44:12 -04:00
|
|
|
#endif
|
2012-03-25 03:55:49 -03:00
|
|
|
#ifndef LOG_PID
|
|
|
|
# define LOG_PID DISABLED
|
|
|
|
#endif
|
2011-07-17 07:31:17 -03:00
|
|
|
|
2011-08-01 07:06:15 -03:00
|
|
|
// calculate the default log_bitmask
|
|
|
|
#define LOGBIT(_s) (LOG_##_s ? MASK_LOG_##_s : 0)
|
|
|
|
|
|
|
|
#define DEFAULT_LOG_BITMASK \
|
2012-03-25 03:55:49 -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)
|
2011-08-01 07:06:15 -03:00
|
|
|
|
2011-05-31 02:29:06 -03:00
|
|
|
// if we are using fast, Disable Medium
|
2011-06-03 02:36:39 -03:00
|
|
|
//#if LOG_ATTITUDE_FAST == ENABLED
|
|
|
|
// #undef LOG_ATTITUDE_MED
|
|
|
|
// #define LOG_ATTITUDE_MED DISABLED
|
|
|
|
//#endif
|
2011-05-31 02:29:06 -03:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
#ifndef DEBUG_PORT
|
|
|
|
# define DEBUG_PORT 0
|
|
|
|
#endif
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
#if DEBUG_PORT == 0
|
|
|
|
# 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
|
|
|
|
# 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
|
|
|
|
# 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
|
|
|
|
# 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
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Navigation defaults
|
|
|
|
//
|
|
|
|
#ifndef WP_RADIUS_DEFAULT
|
2011-12-23 22:44:30 -04:00
|
|
|
# define WP_RADIUS_DEFAULT 1
|
2011-02-17 03:09:13 -04:00
|
|
|
#endif
|
|
|
|
|
2011-09-16 20:54:45 -03:00
|
|
|
#ifndef LOITER_RADIUS
|
2011-11-13 04:25:04 -04:00
|
|
|
# define LOITER_RADIUS 10 // meters for circle mode
|
2011-02-17 03:09:13 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef ALT_HOLD_HOME
|
2011-11-16 04:16:59 -04:00
|
|
|
# define ALT_HOLD_HOME 0 // height to return to Home, 0 = Maintain current altitude
|
2011-02-17 03:09:13 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef USE_CURRENT_ALT
|
|
|
|
# define USE_CURRENT_ALT FALSE
|
|
|
|
#endif
|
|
|
|
|
2011-06-01 02:50:17 -03:00
|
|
|
#ifndef CUT_MOTORS
|
|
|
|
# define CUT_MOTORS 1 // do we cut the motors with no throttle?
|
|
|
|
#endif
|
|
|
|
|
2011-03-19 07:18:21 -03:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// RC override
|
|
|
|
//
|
|
|
|
#ifndef ALLOW_RC_OVERRIDE
|
|
|
|
# define ALLOW_RC_OVERRIDE DISABLED
|
|
|
|
#endif
|
2011-07-17 07:34:05 -03:00
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Developer Items
|
|
|
|
//
|
|
|
|
|
|
|
|
// use this to completely disable the CLI
|
|
|
|
#ifndef CLI_ENABLED
|
|
|
|
# define CLI_ENABLED ENABLED
|
|
|
|
#endif
|
2011-09-05 02:12:13 -03:00
|
|
|
|
2011-10-27 04:35:25 -03:00
|
|
|
// use this to disable the CLI slider switch
|
|
|
|
#ifndef CLI_SLIDER_ENABLED
|
|
|
|
# define CLI_SLIDER_ENABLED ENABLED
|
|
|
|
#endif
|
|
|
|
|
2011-09-05 02:12:13 -03:00
|
|
|
// delay to prevent Xbee bricking, in milliseconds
|
|
|
|
#ifndef MAVLINK_TELEMETRY_PORT_DELAY
|
|
|
|
# define MAVLINK_TELEMETRY_PORT_DELAY 2000
|
|
|
|
#endif
|
2012-01-01 15:44:51 -04:00
|
|
|
|
|
|
|
|
2012-03-03 03:35:39 -04:00
|
|
|
// experimental quaternion code
|
|
|
|
#ifndef QUATERNION_ENABLE
|
|
|
|
# define QUATERNION_ENABLE DISABLED
|
|
|
|
#endif
|
2012-01-01 15:44:51 -04:00
|
|
|
|
2012-04-23 02:16:41 -03:00
|
|
|
|
2012-06-13 09:50:16 -03:00
|
|
|
#ifndef ALTERNATIVE_YAW_MODE
|
|
|
|
# define ALTERNATIVE_YAW_MODE DISABLED
|
|
|
|
#endif
|
|
|
|
|
2012-01-01 15:44:51 -04:00
|
|
|
#endif // __ARDUCOPTER_CONFIG_H__
|