mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_Fence: removed _curr_alt from class
this is only ever set/checked within a function
This commit is contained in:
parent
5e43f068b2
commit
d00a28b9b0
@ -524,7 +524,7 @@ bool AC_Fence::check_fence_alt_max()
|
||||
|
||||
float alt;
|
||||
AP::ahrs().get_relative_position_D_home(alt);
|
||||
_curr_alt = -alt; // translate Down to Up
|
||||
const float _curr_alt = -alt; // translate Down to Up
|
||||
|
||||
// check if we are over the altitude fence
|
||||
if (_curr_alt >= _alt_max) {
|
||||
@ -573,7 +573,7 @@ bool AC_Fence::check_fence_alt_min()
|
||||
|
||||
float alt;
|
||||
AP::ahrs().get_relative_position_D_home(alt);
|
||||
_curr_alt = -alt; // translate Down to Up
|
||||
const float _curr_alt = -alt; // translate Down to Up
|
||||
|
||||
// check if we are under the altitude fence
|
||||
if (_curr_alt <= _alt_min) {
|
||||
@ -625,7 +625,7 @@ bool AC_Fence::auto_enable_fence_floor()
|
||||
|
||||
float alt;
|
||||
AP::ahrs().get_relative_position_D_home(alt);
|
||||
_curr_alt = -alt; // translate Down to Up
|
||||
const float _curr_alt = -alt; // translate Down to Up
|
||||
|
||||
// check if we are over the altitude fence
|
||||
if (!floor_enabled() && _curr_alt >= _alt_min + _margin) {
|
||||
|
@ -251,8 +251,6 @@ private:
|
||||
// other internal variables
|
||||
uint8_t _auto_enable_mask = AC_FENCE_ALL_FENCES; // fences that can be auto-enabled or auto-disabled
|
||||
float _home_distance; // distance from home in meters (provided by main code)
|
||||
float _curr_alt;
|
||||
|
||||
|
||||
// breach information
|
||||
uint8_t _breached_fences; // bitmask holding the fence type that was breached (i.e. AC_FENCE_TYPE_ALT_MIN, AC_FENCE_TYPE_CIRCLE)
|
||||
|
Loading…
Reference in New Issue
Block a user