2011-03-21 04:35:54 -03:00
|
|
|
// Example config file. Use APM_Config.h.reference and the wiki to find additional defines to setup your plane.
|
|
|
|
// Once you upload the code, run the factory "reset" to save all config values to EEPROM.
|
|
|
|
// After reset, use the setup mode to set your radio limits for CH1-4, and to set your flight modes.
|
|
|
|
|
|
|
|
// GPS is auto-selected
|
|
|
|
|
2011-05-09 12:46:56 -03:00
|
|
|
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
2011-03-21 04:35:54 -03:00
|
|
|
|
2011-06-01 02:50:17 -03:00
|
|
|
#define NAV_TEST 1 // 0 = traditional, 1 = rate controlled
|
|
|
|
#define YAW_OPTION 0 // 0 = hybrid rate approach, 1 = offset Yaw approach
|
2011-05-31 02:29:06 -03:00
|
|
|
#define AUTO_RESET_LOITER 1 // enables Loiter to reset it's current location based on stick input.
|
2011-06-01 02:50:17 -03:00
|
|
|
#define CUT_MOTORS 1 // do we cut the motors with no throttle?
|
2011-05-31 02:29:06 -03:00
|
|
|
|
|
|
|
// do we want to have camera stabilization?
|
|
|
|
#define CAMERA_STABILIZER ENABLED
|
2011-05-14 23:04:52 -03:00
|
|
|
|
2011-05-18 20:38:24 -03:00
|
|
|
#define FRAME_CONFIG QUAD_FRAME
|
2011-05-14 23:04:52 -03:00
|
|
|
/*
|
|
|
|
options:
|
2011-05-18 20:38:24 -03:00
|
|
|
QUAD_FRAME
|
|
|
|
TRI_FRAME
|
|
|
|
HEXA_FRAME
|
|
|
|
Y6_FRAME
|
2011-05-23 23:14:18 -03:00
|
|
|
OCTA_FRAME
|
2011-06-12 09:14:10 -03:00
|
|
|
HELI_FRAME
|
2011-05-14 23:04:52 -03:00
|
|
|
*/
|
2011-05-14 23:03:23 -03:00
|
|
|
|
2011-05-18 20:38:24 -03:00
|
|
|
#define FRAME_ORIENTATION X_FRAME
|
|
|
|
/*
|
|
|
|
PLUS_FRAME
|
|
|
|
X_FRAME
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
2011-05-14 23:03:23 -03:00
|
|
|
#define CHANNEL_6_TUNING CH6_NONE
|
2011-04-21 02:15:45 -03:00
|
|
|
/*
|
|
|
|
CH6_NONE
|
|
|
|
CH6_STABLIZE_KP
|
|
|
|
CH6_STABLIZE_KD
|
|
|
|
CH6_BARO_KP
|
|
|
|
CH6_BARO_KD
|
|
|
|
CH6_SONAR_KP
|
|
|
|
CH6_SONAR_KD
|
|
|
|
CH6_Y6_SCALING
|
|
|
|
*/
|
|
|
|
|
2011-03-21 04:35:54 -03:00
|
|
|
//#define ACRO_RATE_TRIGGER 4200
|
|
|
|
// if you want full ACRO mode, set value to 0
|
|
|
|
// if you want mostly stabilize with flips, set value to 4200
|
|
|
|
|
2011-05-14 23:03:23 -03:00
|
|
|
//#define STABILIZE_ROLL_D 0.11
|
|
|
|
//#define STABILIZE_PITCH_D 0.11
|
2011-03-21 04:35:54 -03:00
|
|
|
|
|
|
|
|
|
|
|
// Logging
|
|
|
|
//#define LOG_CURRENT ENABLED
|
|
|
|
|
2011-04-17 02:17:42 -03:00
|
|
|
# define LOG_ATTITUDE_FAST DISABLED
|
|
|
|
# define LOG_ATTITUDE_MED DISABLED
|
2011-04-25 02:12:59 -03:00
|
|
|
# define LOG_GPS ENABLED
|
2011-05-09 01:16:58 -03:00
|
|
|
# define LOG_PM ENABLED
|
2011-04-17 02:17:42 -03:00
|
|
|
# define LOG_CTUN ENABLED
|
2011-04-25 02:12:59 -03:00
|
|
|
# define LOG_NTUN ENABLED
|
|
|
|
# define LOG_MODE ENABLED
|
2011-05-14 23:03:23 -03:00
|
|
|
# define LOG_RAW DISABLED
|
2011-04-25 02:12:59 -03:00
|
|
|
# define LOG_CMD ENABLED
|
2011-04-17 02:17:42 -03:00
|
|
|
# define LOG_CURRENT DISABLED
|
2011-01-23 12:40:03 -04:00
|
|
|
|
2011-05-18 20:38:24 -03:00
|
|
|
|
|
|
|
|
2011-05-27 15:21:55 -03:00
|
|
|
#define MOTOR_LEDS 1 // 0 = off, 1 = on
|
2011-05-18 20:38:24 -03:00
|
|
|
|
|
|
|
#define FR_LED AN12 // Mega PE4 pin, OUT7
|
|
|
|
#define RE_LED AN14 // Mega PE5 pin, OUT6
|
|
|
|
#define RI_LED AN10 // Mega PH4 pin, OUT5
|
2011-06-12 09:14:10 -03:00
|
|
|
#define LE_LED AN8 // Mega PH5 pin, OUT4
|