ardupilot/ArduCopterMega/APM_Config.h
jasonshort 548fc9debf Added support for the AttoPilot Current sensor, Logging current is enabled at 10hz,
Trim is now called again on pitch and roll, now that trimming can be done with adc_offsets. Fixed setup::motors for x frame.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1505 f9c3cf11-9bcb-44bc-f272-b75c42450872
2011-01-17 03:44:12 +00:00

25 lines
882 B
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.
#define GPS_PROTOCOL GPS_PROTOCOL_MTK
#define GCS_PROTOCOL GCS_PROTOCOL_NONE
#define MAGORIENTATION AP_COMPASS_COMPONENTS_UP_PINS_BACK
//#define MAGORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#define ARM_AT_STARTUP 0
// For future development, don't enable unless you know them
// These are all experimental and underwork, jp 23-12-10
//#define ENABLE_EXTRAS ENABLED
//#define ENABLE_EXTRAINIT ENABLED
//#define ENABLE_CAM ENABLED
//#define ENABLE_AM ENABLED
//#define ENABLE_xx ENABLED
// Logging
#define LOG_CURRENT ENABLED