mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: minor change to land mode's logic to use rangefinder
No functional change
This commit is contained in:
parent
8171532dc5
commit
e6b3638d84
@ -234,7 +234,7 @@ void Copter::land_nogps_run()
|
||||
float Copter::get_land_descent_speed()
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
bool rangefinder_ok = rangefinder_state.enabled && (rangefinder.status() == RangeFinder::RangeFinder_Good);
|
||||
bool rangefinder_ok = rangefinder_state.enabled && rangefinder_state.alt_healthy;
|
||||
#else
|
||||
bool rangefinder_ok = false;
|
||||
#endif
|
||||
@ -252,7 +252,7 @@ float Copter::get_land_descent_speed()
|
||||
}
|
||||
|
||||
// if we are above 10m and the rangefinder does not sense anything perform regular alt hold descent
|
||||
if ((target_alt_cm >= LAND_START_ALT) && !(rangefinder_ok && rangefinder_state.alt_healthy)) {
|
||||
if ((target_alt_cm >= LAND_START_ALT) && !rangefinder_ok) {
|
||||
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