ardupilot/ArduCopterMega/APM_Config.h
jasonshort 73be185414 Big update 2.0.38
moved ground start to first arming
added ground start flag
moved throttle_integrator to 50hz loop
CAMERA_STABILIZER deprecated - now always on
renamed current logging bit mask to match APM
added MA filter to PID - D term
Adjusted PIDs based on continued testing and new PID filter
added MASK_LOG_SET_DEFAULTS to match APM
moved some stuff out of ground start into system start where it belonged
Added slower Yaw gains for DCM when the copter is in the air
changed camera output to be none scaled PWM
fixed bug where ground_temperature was unfiltered
shortened Baro startup time
fixed issue with Nav_WP integrator not being reset
RTL no longer yaws towards home
Circle mode for flying a 10m circle around the point where it was engaged. - Not tested at all! Consider Circle mode as alpha.


git-svn-id: https://arducopter.googlecode.com/svn/trunk@2966 f9c3cf11-9bcb-44bc-f272-b75c42450872
2011-07-30 20:42:54 +00:00

53 lines
928 B
C

// Example config file. Take a look at confi.h. Any term define there can be overridden by defining it here.
// GPS is auto-selected
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
//#define HIL_MODE HIL_MODE_ATTITUDE
//#define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
#define FRAME_CONFIG QUAD_FRAME
/*
options:
QUAD_FRAME
TRI_FRAME
HEXA_FRAME
Y6_FRAME
OCTA_FRAME
HELI_FRAME
*/
#define FRAME_ORIENTATION X_FRAME
/*
PLUS_FRAME
X_FRAME
V_FRAME
*/
#define CHANNEL_6_TUNING CH6_NONE
/*
CH6_NONE
CH6_STABILIZE_KP
CH6_STABILIZE_KI
CH6_RATE_KP
CH6_RATE_KI
CH6_THROTTLE_KP
CH6_THROTTLE_KD
CH6_YAW_KP
CH6_YAW_KI
CH6_YAW_RATE_KP
CH6_YAW_RATE_KI
CH6_TOP_BOTTOM_RATIO
CH6_PMAX
CH6_RELAY
*/
// experimental!!
// Yaw is controled by targeting home. you will not have Yaw override.
// flying too close to home may induce spins.
//#define SIMPLE_LOOK_AT_HOME 0