mirror of https://github.com/ArduPilot/ardupilot
added a simple rest of nav_throttle just in case
This commit is contained in:
parent
cc5ab4aebf
commit
f27e9f9ca1
|
@ -531,6 +531,9 @@ static void set_mode(byte mode)
|
|||
if(throttle_mode == THROTTLE_MANUAL){
|
||||
// reset all of the throttle iterms
|
||||
update_throttle_cruise();
|
||||
|
||||
// reset auto_throttle
|
||||
nav_throttle = 0;
|
||||
}else {
|
||||
// an automatic throttle
|
||||
init_throttle_cruise();
|
||||
|
|
Loading…
Reference in New Issue