ardupilot/ArduCopterMega/APM_Config.h
jasonshort 66b8cebb14 added comments for frame types
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2330 f9c3cf11-9bcb-44bc-f272-b75c42450872
2011-05-16 06:05:08 +00:00

56 lines
1.5 KiB
C

// 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
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#define NAV_TEST 0 // 0 = traditional, 1 = rate controlled
#define FRAME_CONFIG QUADX_FRAME
/*
options:
QUADP_FRAME // the classic plus configuration
QUADX_FRAME // the superior X configuration
TRI_FRAME // three props with a servo on the tail for yaw
HEXAP_FRAME // you have more motors than sense (6)
HEXAX_FRAME // you like scaring children in the park
Y6_FRAME // the motors are stacked on a Tri frame
*/
#define CHANNEL_6_TUNING CH6_NONE
/*
CH6_NONE
CH6_STABLIZE_KP
CH6_STABLIZE_KD
CH6_BARO_KP
CH6_BARO_KD
CH6_SONAR_KP
CH6_SONAR_KD
CH6_Y6_SCALING
*/
//#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
//#define STABILIZE_ROLL_D 0.11
//#define STABILIZE_PITCH_D 0.11
// Logging
//#define LOG_CURRENT ENABLED
# define LOG_ATTITUDE_FAST DISABLED
# define LOG_ATTITUDE_MED DISABLED
# define LOG_GPS ENABLED
# define LOG_PM ENABLED
# define LOG_CTUN ENABLED
# define LOG_NTUN ENABLED
# define LOG_MODE ENABLED
# define LOG_RAW DISABLED
# define LOG_CMD ENABLED
# define LOG_CURRENT DISABLED