AC_PrecLand: remove code duplication and use the same logic as the other backends (<= instead of <)

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2024-02-14 14:14:51 +01:00 committed by Andrew Tridgell
parent 0f6f738a33
commit 4d7fc1fe46
2 changed files with 5 additions and 10 deletions

View File

@ -39,19 +39,14 @@ void AC_PrecLand_SITL::update()
_have_los_meas = _have_los_meas && AP_HAL::millis() - _los_meas_time_ms <= 1000;
}
bool AC_PrecLand_SITL::have_los_meas() {
return AP_HAL::millis() - _los_meas_time_ms < 1000;
}
// provides a unit vector towards the target in body frame
// returns same as have_los_meas()
bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) {
if (AP_HAL::millis() - _los_meas_time_ms > 1000) {
// no measurement for a full second; no vector available
return false;
}
if (have_los_meas()) {
ret = _los_meas_body;
return true;
}
return false;
}
#endif // AC_PRECLAND_SITL_ENABLED

View File

@ -33,7 +33,7 @@ public:
uint32_t los_meas_time_ms() override { return _los_meas_time_ms; }
// return true if there is a valid los measurement available
bool have_los_meas() override;
bool have_los_meas() override { return _have_los_meas; }
// returns distance to target in meters (0 means distance is not known)
float distance_to_target() override { return _distance_to_target; }