SITL: check if we are over precland base

This commit is contained in:
Pierre Kancir 2021-02-08 13:15:01 +01:00 committed by Andrew Tridgell
parent cec82214d8
commit 9a6d4e3af1
2 changed files with 4 additions and 1 deletions

View File

@ -51,7 +51,7 @@ const AP_Param::GroupInfo SIM_Precland::var_info[] = {
// @Param: HEIGHT
// @DisplayName: Precland device origin's height above sealevel
// @Description: Precland device origin's height above sealevel
// @Description: Precland device origin's height above sealevel assume a 2x2m square as station base
// @Units: cm
// @Increment: 1
// @Range: 0 10000
@ -129,6 +129,8 @@ void SIM_Precland::update(const Location &loc, const Vector3f &position)
return;
}
center = center * 0.01f; // cm to m
_over_precland_base = origin_center.get_distance(loc) <= 2.0f;
const uint32_t now = AP_HAL::millis();
if (now - _last_update_ms < 1000.0f * (1.0f / _rate)) {
return;

View File

@ -50,6 +50,7 @@ public:
AP_Int32 _rate;
AP_Float _alt_limit;
AP_Float _dist_limit;
bool _over_precland_base;
enum PreclandType {
PRECLAND_TYPE_CYLINDER = 0,