mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
SITL: check if we are over precland base
This commit is contained in:
parent
cec82214d8
commit
9a6d4e3af1
@ -51,7 +51,7 @@ const AP_Param::GroupInfo SIM_Precland::var_info[] = {
|
|||||||
|
|
||||||
// @Param: HEIGHT
|
// @Param: HEIGHT
|
||||||
// @DisplayName: Precland device origin's height above sealevel
|
// @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
|
// @Units: cm
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @Range: 0 10000
|
// @Range: 0 10000
|
||||||
@ -129,6 +129,8 @@ void SIM_Precland::update(const Location &loc, const Vector3f &position)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
center = center * 0.01f; // cm to m
|
center = center * 0.01f; // cm to m
|
||||||
|
_over_precland_base = origin_center.get_distance(loc) <= 2.0f;
|
||||||
|
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
if (now - _last_update_ms < 1000.0f * (1.0f / _rate)) {
|
if (now - _last_update_ms < 1000.0f * (1.0f / _rate)) {
|
||||||
return;
|
return;
|
||||||
|
@ -50,6 +50,7 @@ public:
|
|||||||
AP_Int32 _rate;
|
AP_Int32 _rate;
|
||||||
AP_Float _alt_limit;
|
AP_Float _alt_limit;
|
||||||
AP_Float _dist_limit;
|
AP_Float _dist_limit;
|
||||||
|
bool _over_precland_base;
|
||||||
|
|
||||||
enum PreclandType {
|
enum PreclandType {
|
||||||
PRECLAND_TYPE_CYLINDER = 0,
|
PRECLAND_TYPE_CYLINDER = 0,
|
||||||
|
Loading…
Reference in New Issue
Block a user