mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_PrecLand: remove code duplication and use the same logic as the other backends (<= instead of <)
This commit is contained in:
parent
0f6f738a33
commit
4d7fc1fe46
@ -39,19 +39,14 @@ void AC_PrecLand_SITL::update()
|
|||||||
_have_los_meas = _have_los_meas && AP_HAL::millis() - _los_meas_time_ms <= 1000;
|
_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
|
// provides a unit vector towards the target in body frame
|
||||||
// returns same as have_los_meas()
|
// returns same as have_los_meas()
|
||||||
bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) {
|
bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) {
|
||||||
if (AP_HAL::millis() - _los_meas_time_ms > 1000) {
|
if (have_los_meas()) {
|
||||||
// no measurement for a full second; no vector available
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
ret = _los_meas_body;
|
ret = _los_meas_body;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // AC_PRECLAND_SITL_ENABLED
|
#endif // AC_PRECLAND_SITL_ENABLED
|
||||||
|
@ -33,7 +33,7 @@ public:
|
|||||||
uint32_t los_meas_time_ms() override { return _los_meas_time_ms; }
|
uint32_t los_meas_time_ms() override { return _los_meas_time_ms; }
|
||||||
|
|
||||||
// return true if there is a valid los measurement available
|
// 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)
|
// returns distance to target in meters (0 means distance is not known)
|
||||||
float distance_to_target() override { return _distance_to_target; }
|
float distance_to_target() override { return _distance_to_target; }
|
||||||
|
Loading…
Reference in New Issue
Block a user