mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-07 08:28:30 -04:00
35bf288abd
Before: -> After Stabilize P –> Stabilize P (Use NG values, or 8.3 x the older AC2 value) Stabilize I –> Stabilize I (Stays same value) Stabilize D –> Rate P (Stays same value) –> Rate I (new) Added a new value – an I term for rate. The old stabilization routines did not use this term. Please refer to the config.h file to read more about the new PIDs. Added framework for using DCM corrected Accelerometer rates. Code is commented out for now. Added set home at Arming. Crosstrack is now a full PID loop, rather than just a P gain for more control. Throttle now slews when switching out of Alt hold or Auto modes for less jarring transitions Sonar and Baro PIDs are now combined into a throttle PID Yaw control is completely re-written. Added Octa_Quad support - Max git-svn-id: https://arducopter.googlecode.com/svn/trunk@2836 f9c3cf11-9bcb-44bc-f272-b75c42450872
50 lines
871 B
C
50 lines
871 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 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
|
|
*/
|
|
|
|
// 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
|