AC_Fence: get home distance directly from ahrs
This commit is contained in:
parent
20e295c23a
commit
0f94fde434
@ -241,6 +241,12 @@ bool AC_Fence::check_fence_circle()
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Vector2f home;
|
||||||
|
if (_ahrs.get_relative_position_NE_home(home)) {
|
||||||
|
// we (may) remain breached if we can't update home
|
||||||
|
_home_distance = home.length();
|
||||||
|
}
|
||||||
|
|
||||||
// check if we are outside the fence
|
// check if we are outside the fence
|
||||||
if (_home_distance >= _circle_radius) {
|
if (_home_distance >= _circle_radius) {
|
||||||
|
|
||||||
|
@ -95,13 +95,6 @@ public:
|
|||||||
/// has no effect if no breaches have occurred
|
/// has no effect if no breaches have occurred
|
||||||
void manual_recovery_start();
|
void manual_recovery_start();
|
||||||
|
|
||||||
///
|
|
||||||
/// time saving methods to piggy-back on main code's calculations
|
|
||||||
///
|
|
||||||
|
|
||||||
/// set_home_distance - update vehicle's distance from home in meters - required for circular horizontal fence monitoring
|
|
||||||
void set_home_distance(float distance) { _home_distance = distance; }
|
|
||||||
|
|
||||||
///
|
///
|
||||||
/// polygon related methods
|
/// polygon related methods
|
||||||
///
|
///
|
||||||
|
Loading…
Reference in New Issue
Block a user