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
|
|
|
//
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//
|
|
|
|
// 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
|
|
|
///
|
2011-02-24 01:56:59 -04:00
|
|
|
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
2010-12-19 12:40:33 -04:00
|
|
|
///
|
|
|
|
/// 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
|
|
|
///
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
// Just so that it's completely clear...
|
|
|
|
#define ENABLED 1
|
|
|
|
#define DISABLED 0
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// HARDWARE CONFIGURATION AND CONNECTIONS
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// FRAME_CONFIG
|
2011-02-19 22:03:01 -04:00
|
|
|
//
|
2010-12-19 12:40:33 -04:00
|
|
|
#ifndef FRAME_CONFIG
|
|
|
|
# define FRAME_CONFIG PLUS_FRAME
|
|
|
|
#endif
|
|
|
|
|
2011-02-20 19:09:28 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Sonar
|
|
|
|
//
|
|
|
|
#ifndef SONAR_PIN
|
|
|
|
# define SONAR_PIN AP_RANGEFINDER_PITOT_TUBE
|
|
|
|
#endif
|
|
|
|
|
2011-02-24 01:56:59 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// AIRSPEED_SENSOR
|
|
|
|
// AIRSPEED_RATIO
|
|
|
|
//
|
|
|
|
#ifndef AIRSPEED_SENSOR
|
|
|
|
# define AIRSPEED_SENSOR DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef AIRSPEED_RATIO
|
|
|
|
# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution
|
|
|
|
#endif
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// HIL_PROTOCOL OPTIONAL
|
|
|
|
// HIL_MODE OPTIONAL
|
|
|
|
// HIL_PORT OPTIONAL
|
|
|
|
|
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
|
|
|
|
|
|
|
|
# undef GPS_PROTOCOL
|
|
|
|
# define GPS_PROTOCOL GPS_PROTOCOL_NONE
|
|
|
|
|
|
|
|
#ifndef HIL_PROTOCOL
|
|
|
|
# error Must define HIL_PROTOCOL if HIL_MODE is not disabled
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef HIL_PORT
|
|
|
|
# error Must define HIL_PORT if HIL_PROTOCOL is set
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
// If we are in XPlane, diasble the mag
|
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
|
|
|
|
|
|
|
|
// check xplane settings
|
|
|
|
#if HIL_PROTOCOL == HIL_PROTOCOL_XPLANE
|
|
|
|
|
|
|
|
// MAGNETOMETER not supported by XPLANE
|
|
|
|
# undef MAGNETOMETER
|
|
|
|
# define MAGNETOMETER DISABLED
|
|
|
|
|
|
|
|
# if HIL_MODE != HIL_MODE_ATTITUDE
|
|
|
|
# error HIL_PROTOCOL_XPLANE requires HIL_MODE_ATTITUDE
|
|
|
|
# endif
|
|
|
|
|
|
|
|
#endif
|
|
|
|
#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
|
|
|
|
# define GPS_PROTOCOL GPS_PROTOCOL_AUTO
|
|
|
|
#endif
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// GCS_PROTOCOL
|
|
|
|
// GCS_PORT
|
|
|
|
//
|
|
|
|
#ifndef GCS_PROTOCOL
|
2011-03-26 03:35:52 -03:00
|
|
|
# define GCS_PROTOCOL GCS_PROTOCOL_MAVLINK
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// 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 BATTERY_TYPE
|
|
|
|
# define BATTERY_TYPE 0
|
|
|
|
#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
|
|
|
|
# define VOLT_DIV_RATIO 3.0
|
|
|
|
#endif
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2011-01-16 23:44:12 -04:00
|
|
|
#ifndef CURR_VOLT_DIV_RATIO
|
|
|
|
# define CURR_VOLT_DIV_RATIO 15.7
|
|
|
|
#endif
|
|
|
|
#ifndef CURR_AMP_DIV_RATIO
|
|
|
|
# define CURR_AMP_DIV_RATIO 30.35
|
|
|
|
#endif
|
2011-02-19 22:03:01 -04:00
|
|
|
#ifndef CURR_AMP_HOURS
|
|
|
|
# define CURR_AMP_HOURS 2000
|
|
|
|
#endif
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// INPUT_VOLTAGE
|
|
|
|
//
|
|
|
|
#ifndef INPUT_VOLTAGE
|
|
|
|
# define INPUT_VOLTAGE 5.0
|
|
|
|
#endif
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// MAGNETOMETER
|
2011-02-24 01:56:59 -04:00
|
|
|
#ifndef MAGNETOMETER
|
|
|
|
# define MAGNETOMETER DISABLED
|
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
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// RADIO CONFIGURATION
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// FLIGHT_MODE
|
|
|
|
// FLIGHT_MODE_CHANNEL
|
|
|
|
//
|
|
|
|
#ifndef FLIGHT_MODE_CHANNEL
|
|
|
|
# define FLIGHT_MODE_CHANNEL CH_5
|
|
|
|
#endif
|
|
|
|
#if (FLIGHT_MODE_CHANNEL != CH_5) && (FLIGHT_MODE_CHANNEL != CH_6) && (FLIGHT_MODE_CHANNEL != CH_7) && (FLIGHT_MODE_CHANNEL != CH_8)
|
|
|
|
# error XXX
|
|
|
|
# error XXX You must set FLIGHT_MODE_CHANNEL to 5, 6, 7 or 8
|
|
|
|
# error XXX
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#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
|
|
|
|
# define THROTTLE_FAILSAFE DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef THROTTE_FS_VALUE
|
|
|
|
# define THROTTLE_FS_VALUE 975
|
|
|
|
#endif
|
|
|
|
#ifndef THROTTLE_FAILSAFE_ACTION
|
|
|
|
# define THROTTLE_FAILSAFE_ACTION 2
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// STARTUP BEHAVIOUR
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// GROUND_START_DELAY
|
|
|
|
//
|
|
|
|
#ifndef GROUND_START_DELAY
|
|
|
|
# define GROUND_START_DELAY 0
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// FLIGHT AND NAVIGATION CONTROL
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// ACRO Rate Control
|
|
|
|
|
|
|
|
#ifndef ACRO_RATE_ROLL_P
|
|
|
|
# define ACRO_RATE_ROLL_P .190
|
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_ROLL_I
|
|
|
|
# define ACRO_RATE_ROLL_I 0.0
|
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_ROLL_D
|
|
|
|
# define ACRO_RATE_ROLL_D 0.0
|
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_ROLL_IMAX
|
|
|
|
# define ACRO_RATE_ROLL_IMAX 20
|
|
|
|
#endif
|
2011-02-17 03:09:13 -04:00
|
|
|
# define ACRO_RATE_ROLL_IMAX_CENTIDEGREE ACRO_RATE_ROLL_IMAX * 100
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
#ifndef ACRO_RATE_PITCH_P
|
|
|
|
# define ACRO_RATE_PITCH_P .190
|
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_PITCH_I
|
|
|
|
# define ACRO_RATE_PITCH_I 0.0
|
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_PITCH_D
|
|
|
|
# define ACRO_RATE_PITCH_D 0.0
|
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_PITCH_IMAX
|
2011-02-19 22:03:01 -04:00
|
|
|
# define ACRO_RATE_PITCH_IMAX 20
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-02-17 03:09:13 -04:00
|
|
|
#define ACRO_RATE_PITCH_IMAX_CENTIDEGREE ACRO_RATE_PITCH_IMAX * 100
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
#ifndef ACRO_RATE_YAW_P
|
2011-04-10 17:31:33 -03:00
|
|
|
# define ACRO_RATE_YAW_P .2 // used to control response in turning
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_YAW_I
|
|
|
|
# define ACRO_RATE_YAW_I 0.0
|
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_YAW_D
|
2011-02-21 16:58:10 -04:00
|
|
|
# define ACRO_RATE_YAW_D 0.05
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef ACRO_RATE_YAW_IMAX
|
2011-01-02 16:34:42 -04:00
|
|
|
# define ACRO_RATE_YAW_IMAX 0
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-02-17 03:09:13 -04:00
|
|
|
# define ACRO_RATE_YAW_IMAX_CENTIDEGREE ACRO_RATE_YAW_IMAX * 100
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-01-25 01:53:36 -04:00
|
|
|
#ifndef ACRO_RATE_TRIGGER
|
2011-04-08 16:13:31 -03:00
|
|
|
# define ACRO_RATE_TRIGGER 0
|
2011-01-25 01:53:36 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// STABILZE Angle Control
|
|
|
|
//
|
|
|
|
#ifndef STABILIZE_ROLL_P
|
2010-12-30 03:40:57 -04:00
|
|
|
# define STABILIZE_ROLL_P 0.6
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef STABILIZE_ROLL_I
|
2011-04-10 17:31:33 -03:00
|
|
|
# define STABILIZE_ROLL_I 0.1 //
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef STABILIZE_ROLL_D
|
2011-04-10 17:31:33 -03:00
|
|
|
# define STABILIZE_ROLL_D 0.135
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef STABILIZE_ROLL_IMAX
|
2011-04-10 17:31:33 -03:00
|
|
|
# define STABILIZE_ROLL_IMAX 10 // 10 degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef STABILIZE_PITCH_P
|
2010-12-30 03:40:57 -04:00
|
|
|
# define STABILIZE_PITCH_P 0.6
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef STABILIZE_PITCH_I
|
2011-04-10 17:31:33 -03:00
|
|
|
# define STABILIZE_PITCH_I 0.1
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef STABILIZE_PITCH_D
|
2011-04-10 17:31:33 -03:00
|
|
|
# define STABILIZE_PITCH_D 0.135
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef STABILIZE_PITCH_IMAX
|
2011-04-10 17:31:33 -03:00
|
|
|
# define STABILIZE_PITCH_IMAX 10
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// YAW Control
|
|
|
|
//
|
|
|
|
#ifndef YAW_P
|
2011-04-10 17:31:33 -03:00
|
|
|
# define YAW_P 0.35 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef YAW_I
|
2011-04-10 17:31:33 -03:00
|
|
|
# define YAW_I 0.0 // Always 0
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef YAW_D
|
2011-04-10 17:31:33 -03:00
|
|
|
# define YAW_D 0.175 //
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef YAW_IMAX
|
2011-04-10 17:31:33 -03:00
|
|
|
# define YAW_IMAX 0 // Always 0
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Autopilot control limits
|
|
|
|
//
|
|
|
|
// how much to we pitch towards the target
|
|
|
|
#ifndef PITCH_MAX
|
2011-04-10 17:31:33 -03:00
|
|
|
# define PITCH_MAX 25 // degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Navigation control gains
|
|
|
|
//
|
|
|
|
#ifndef NAV_P
|
2011-02-07 02:19:19 -04:00
|
|
|
# define NAV_P 2.0
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef NAV_I
|
2011-03-15 02:54:48 -03:00
|
|
|
# define NAV_I 0.1
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef NAV_D
|
2011-04-10 17:31:33 -03:00
|
|
|
# define NAV_D 0.00 // should always be 0
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef NAV_IMAX
|
2011-04-10 17:31:33 -03:00
|
|
|
# define NAV_IMAX 250 // 250 degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Throttle control gains
|
|
|
|
//
|
2011-01-09 22:18:49 -04:00
|
|
|
#ifndef THROTTLE_BARO_P
|
2011-02-13 18:32:34 -04:00
|
|
|
# define THROTTLE_BARO_P 0.25
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-01-09 22:18:49 -04:00
|
|
|
#ifndef THROTTLE_BARO_I
|
2011-02-13 18:32:34 -04:00
|
|
|
# define THROTTLE_BARO_I 0.01
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-01-09 22:18:49 -04:00
|
|
|
#ifndef THROTTLE_BARO_D
|
2011-02-13 01:21:32 -04:00
|
|
|
# define THROTTLE_BARO_D 0.2
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
2011-01-09 22:18:49 -04:00
|
|
|
#ifndef THROTTLE_BARO_IMAX
|
2011-02-13 01:21:32 -04:00
|
|
|
# define THROTTLE_BARO_IMAX 50
|
2011-01-09 22:18:49 -04:00
|
|
|
#endif
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-01-09 22:18:49 -04:00
|
|
|
|
|
|
|
#ifndef THROTTLE_SONAR_P
|
2011-02-21 00:30:56 -04:00
|
|
|
# define THROTTLE_SONAR_P .3
|
2011-01-09 22:18:49 -04:00
|
|
|
#endif
|
|
|
|
#ifndef THROTTLE_SONAR_I
|
2011-02-21 00:30:56 -04:00
|
|
|
# define THROTTLE_SONAR_I 0.01
|
2011-01-09 22:18:49 -04:00
|
|
|
#endif
|
|
|
|
#ifndef THROTTLE_SONAR_D
|
2011-04-08 16:13:31 -03:00
|
|
|
# define THROTTLE_SONAR_D 0.03
|
2011-01-09 22:18:49 -04:00
|
|
|
#endif
|
|
|
|
#ifndef THROTTLE_SONAR_IMAX
|
2011-02-21 00:30:56 -04:00
|
|
|
# define THROTTLE_SONAR_IMAX 50
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Crosstrack compensation
|
|
|
|
//
|
|
|
|
#ifndef XTRACK_GAIN
|
2011-02-17 03:09:13 -04:00
|
|
|
# define XTRACK_GAIN 1 // deg/m
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
#ifndef XTRACK_ENTRY_ANGLE
|
2011-02-17 03:09:13 -04:00
|
|
|
# define XTRACK_ENTRY_ANGLE 30 // deg
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// DEBUGGING
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// DEBUG_LEVEL
|
|
|
|
//
|
|
|
|
#ifndef DEBUG_LEVEL
|
|
|
|
# define DEBUG_LEVEL SEVERITY_LOW
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Dataflash logging control
|
|
|
|
//
|
|
|
|
#ifndef LOG_ATTITUDE_FAST
|
|
|
|
# define LOG_ATTITUDE_FAST DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_ATTITUDE_MED
|
|
|
|
# define LOG_ATTITUDE_MED ENABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_GPS
|
|
|
|
# define LOG_GPS ENABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_PM
|
|
|
|
# define LOG_PM ENABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_CTUN
|
|
|
|
# define LOG_CTUN DISABLED
|
|
|
|
#endif
|
|
|
|
#ifndef LOG_NTUN
|
|
|
|
# define LOG_NTUN DISABLED
|
|
|
|
#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-01-16 23:44:12 -04:00
|
|
|
#ifndef LOG_CURRENT
|
|
|
|
# define LOG_CURRENT DISABLED
|
|
|
|
#endif
|
2010-12-19 12:40:33 -04: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
|
|
|
|
# define WP_RADIUS_DEFAULT 3
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef LOITER_RADIUS_DEFAULT
|
|
|
|
# define LOITER_RADIUS_DEFAULT 10
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef ALT_HOLD_HOME
|
|
|
|
# define ALT_HOLD_HOME 8
|
|
|
|
#endif
|
2011-02-25 01:33:39 -04:00
|
|
|
#define ALT_HOLD_HOME_CM ALT_HOLD_HOME * 100
|
2011-02-17 03:09:13 -04:00
|
|
|
|
|
|
|
#ifndef USE_CURRENT_ALT
|
|
|
|
# define USE_CURRENT_ALT FALSE
|
|
|
|
#endif
|
|
|
|
|
2011-03-19 07:18:21 -03:00
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
// RC override
|
|
|
|
//
|
|
|
|
#ifndef ALLOW_RC_OVERRIDE
|
|
|
|
# define ALLOW_RC_OVERRIDE DISABLED
|
|
|
|
#endif
|