mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
undo config change
This commit is contained in:
parent
a052c25899
commit
d42f2e230e
@ -6,11 +6,11 @@
|
|||||||
|
|
||||||
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
||||||
//#define GCS_PROTOCOL GCS_PROTOCOL_NONE
|
//#define GCS_PROTOCOL GCS_PROTOCOL_NONE
|
||||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
//#define HIL_MODE HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
//#define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
|
//#define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
|
||||||
|
|
||||||
#define FRAME_CONFIG HELI_FRAME
|
#define FRAME_CONFIG QUAD_FRAME
|
||||||
/*
|
/*
|
||||||
options:
|
options:
|
||||||
QUAD_FRAME
|
QUAD_FRAME
|
||||||
@ -53,43 +53,3 @@
|
|||||||
|
|
||||||
//#define RATE_ROLL_I 0.18
|
//#define RATE_ROLL_I 0.18
|
||||||
//#define RATE_PITCH_I 0.18
|
//#define RATE_PITCH_I 0.18
|
||||||
|
|
||||||
|
|
||||||
#define AUTO_RESET_LOITER 0
|
|
||||||
#define FRAME_CONFIG HELI_FRAME
|
|
||||||
|
|
||||||
// DEFAULT PIDS
|
|
||||||
|
|
||||||
// roll
|
|
||||||
#define STABILIZE_ROLL_P 0.70
|
|
||||||
#define STABILIZE_ROLL_I 0.025
|
|
||||||
#define STABILIZE_ROLL_D 0.04
|
|
||||||
#define STABILIZE_ROLL_IMAX 7
|
|
||||||
|
|
||||||
//pitch
|
|
||||||
#define STABILIZE_PITCH_P 0.70
|
|
||||||
#define STABILIZE_PITCH_I 0.025
|
|
||||||
#define STABILIZE_PITCH_D 0.04
|
|
||||||
#define STABILIZE_PITCH_IMAX 7
|
|
||||||
|
|
||||||
// yaw stablise
|
|
||||||
#define STABILIZE_YAW_P 0.7
|
|
||||||
#define STABILIZE_YAW_I 0.02
|
|
||||||
#define STABILIZE_YAW_D 0.0
|
|
||||||
|
|
||||||
// yaw rate
|
|
||||||
#define RATE_YAW_P 0.135
|
|
||||||
#define RATE_YAW_I 0.0
|
|
||||||
#define RATE_YAW_D 0.0
|
|
||||||
|
|
||||||
// throttle
|
|
||||||
#define THROTTLE_P 0.2
|
|
||||||
#define THROTTLE_I 0.001
|
|
||||||
#define THROTTLE_IMAX 100
|
|
||||||
|
|
||||||
// navigation
|
|
||||||
#define NAV_LOITER_P 1.1
|
|
||||||
#define NAV_LOITER_I 0.03
|
|
||||||
#define NAV_LOITER_D 0.02
|
|
||||||
#define NAV_LOITER_IMAX 10
|
|
||||||
|
|
||||||
|
@ -143,7 +143,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
|||||||
g.rc_1.servo_out,
|
g.rc_1.servo_out,
|
||||||
g.rc_2.servo_out,
|
g.rc_2.servo_out,
|
||||||
g.rc_3.radio_out,
|
g.rc_3.radio_out,
|
||||||
g.rc_4.servo_out
|
g.rc_4.servo_out,
|
||||||
0,
|
0,
|
||||||
0,
|
0,
|
||||||
0,
|
0,
|
||||||
|
Loading…
Reference in New Issue
Block a user