mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Added Landing throttle control to force down the copter
This commit is contained in:
parent
b493cb1e55
commit
6d0f078fdd
@ -359,16 +359,20 @@ static bool verify_land()
|
|||||||
// remenber altitude for climb_rate
|
// remenber altitude for climb_rate
|
||||||
old_alt = current_loc.alt;
|
old_alt = current_loc.alt;
|
||||||
|
|
||||||
if ((current_loc.alt - home.alt) < 250){
|
if ((current_loc.alt - home.alt) < 200){
|
||||||
// don't bank to hold position
|
// don't bank to hold position
|
||||||
wp_control = NO_NAV_MODE;
|
wp_control = NO_NAV_MODE;
|
||||||
// try and come down faster
|
// try and come down faster
|
||||||
// by setting next_WP really low.
|
landing_boost++;
|
||||||
set_new_altitude(-1000);
|
landing_boost = min(landing_boost, 20);
|
||||||
|
}else{
|
||||||
|
landing_boost = 0;
|
||||||
|
wp_control = LOITER_MODE;
|
||||||
}
|
}
|
||||||
|
|
||||||
if((current_loc.alt - home.alt) < 100 && velocity_land <= 50){
|
if((current_loc.alt - home.alt) < 100 && velocity_land <= 50){
|
||||||
land_complete = true;
|
land_complete = true;
|
||||||
|
landing_boost = 0;
|
||||||
|
|
||||||
// reset old_alt
|
// reset old_alt
|
||||||
old_alt = 0;
|
old_alt = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user