mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
2.0.39
Added a limiter to Throttle_slew to not make the throttle go past 800. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2989 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
f951ffb602
commit
a0f61fd29e
@ -794,6 +794,8 @@ static void fifty_hz_loop()
|
||||
else if (throttle_slew > 0)
|
||||
throttle_slew--;
|
||||
|
||||
throttle_slew = min((800 - throttle), throttle_slew);
|
||||
|
||||
# if HIL_MODE == HIL_MODE_DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
|
||||
Log_Write_Attitude();
|
||||
@ -1562,8 +1564,13 @@ static void auto_throttle()
|
||||
// apply throttle control
|
||||
g.rc_3.servo_out = get_throttle(nav_throttle - throttle_slew);
|
||||
|
||||
// remember throttle offset
|
||||
throttle_slew = g.rc_3.servo_out - g.rc_3.control_in;
|
||||
if(motor_armed){
|
||||
// remember throttle offset
|
||||
throttle_slew = g.rc_3.servo_out - g.rc_3.control_in;
|
||||
}else{
|
||||
// don't allow
|
||||
throttle_slew = 0;
|
||||
}
|
||||
|
||||
// clear the new data flag
|
||||
invalid_throttle = false;
|
||||
|
Loading…
Reference in New Issue
Block a user