mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: while landing use land-speed from 10m above home
Previously vehicle was switching to land-speed at 10m above the origin
This commit is contained in:
parent
ffd86744ce
commit
39dc2d7176
@ -239,7 +239,7 @@ float Copter::get_land_descent_speed()
|
||||
bool sonar_ok = false;
|
||||
#endif
|
||||
// if we are above 10m and the sonar does not sense anything perform regular alt hold descent
|
||||
if (pos_control.get_pos_target().z >= pv_alt_above_origin(LAND_START_ALT) && !(sonar_ok && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
if ((pv_alt_above_home(pos_control.get_pos_target().z) >= LAND_START_ALT) && !(sonar_ok && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
if (g.land_speed_high > 0) {
|
||||
// user has asked for a different landing speed than normal descent rate
|
||||
return -abs(g.land_speed_high);
|
||||
|
Loading…
Reference in New Issue
Block a user