mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
ArduCopter: modified altitude hold so that 1 second slow down period is executed after pilot moves throttle back into deadzone
This commit is contained in:
parent
4371fdda6c
commit
7a31e4e660
@ -1824,12 +1824,16 @@ void update_throttle_mode(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// allow 1 second of slow down after pilot moves throttle back into deadzone
|
||||||
if(reset_throttle_counter > 0){
|
if(reset_throttle_counter > 0){
|
||||||
reset_throttle_counter--;
|
reset_throttle_counter--;
|
||||||
|
// if 1 second has passed set the target altitude to the current altitude
|
||||||
if(reset_throttle_counter == 0){
|
if(reset_throttle_counter == 0){
|
||||||
force_new_altitude(max(current_loc.alt, 100));
|
force_new_altitude(max(current_loc.alt, 100));
|
||||||
}else{
|
}else{
|
||||||
nav_throttle = get_throttle_rate(0);
|
nav_throttle = get_throttle_rate(0);
|
||||||
|
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user