mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_Fence: accept curr_alt parameter instead of getting alt from inav
This commit is contained in:
parent
0f9e50d61c
commit
05fda4ee4c
@ -111,7 +111,7 @@ bool AC_Fence::pre_arm_check() const
|
|||||||
}
|
}
|
||||||
|
|
||||||
/// check_fence - returns the fence type that has been breached (if any)
|
/// check_fence - returns the fence type that has been breached (if any)
|
||||||
uint8_t AC_Fence::check_fence()
|
uint8_t AC_Fence::check_fence(float curr_alt)
|
||||||
{
|
{
|
||||||
uint8_t ret = AC_FENCE_TYPE_NONE;
|
uint8_t ret = AC_FENCE_TYPE_NONE;
|
||||||
|
|
||||||
@ -131,9 +131,6 @@ uint8_t AC_Fence::check_fence()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// get current altitude in meters
|
|
||||||
float curr_alt = _inav.get_altitude() * 0.01f;
|
|
||||||
|
|
||||||
// altitude fence check
|
// altitude fence check
|
||||||
if ((_enabled_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
|
if ((_enabled_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
|
||||||
|
|
||||||
|
@ -52,7 +52,7 @@ public:
|
|||||||
///
|
///
|
||||||
|
|
||||||
/// check_fence - returns the fence type that has been breached (if any)
|
/// check_fence - returns the fence type that has been breached (if any)
|
||||||
uint8_t check_fence();
|
uint8_t check_fence(float curr_alt);
|
||||||
|
|
||||||
/// get_breaches - returns bit mask of the fence types that have been breached
|
/// get_breaches - returns bit mask of the fence types that have been breached
|
||||||
uint8_t get_breaches() const { return _breached_fences; }
|
uint8_t get_breaches() const { return _breached_fences; }
|
||||||
|
Loading…
Reference in New Issue
Block a user