Added Yaw control when descending in Alt hold
lowered kP & kD for Alt hold a tad
Adjusted RTL behavior to do speed control up to 4m to home, then go into Loiter
Fixed issue with AUTO not getting proper input.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2873 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-07-16 22:32:54 +00:00
parent af8afecbb8
commit df26281296

View File

@ -1017,10 +1017,10 @@ void update_current_flight_mode(void)
g.rc_2.servo_out = g.rc_2.control_mix(nav_pitch);
// Roll control
g.rc_1.servo_out = get_stabilize_roll(g.rc_1.control_in);
g.rc_1.servo_out = get_stabilize_roll(g.rc_1.servo_out);
// Pitch control
g.rc_2.servo_out = get_stabilize_pitch(g.rc_2.control_in);
g.rc_2.servo_out = get_stabilize_pitch(g.rc_2.servo_out);
// Throttle control
if(invalid_throttle){