AC_Fence: make member pointer to AP_InertialNav const, remove unused

gps-pointer member
This commit is contained in:
Tobias 2013-07-24 16:05:21 +02:00 committed by Randy Mackay
parent 7564cc02af
commit 596c7a25b7
2 changed files with 4 additions and 4 deletions

View File

@ -55,7 +55,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] PROGMEM = {
};
/// Default constructor.
AC_Fence::AC_Fence(AP_InertialNav* inav) :
AC_Fence::AC_Fence(const AP_InertialNav* inav) :
_inav(inav),
_alt_max_backup(0),
_circle_radius_backup(0),
@ -232,4 +232,4 @@ float AC_Fence::get_breach_distance(uint8_t fence_type) const
// we don't recognise the fence type so just return 0
return 0;
}
}

View File

@ -32,7 +32,7 @@ class AC_Fence
public:
/// Constructor
AC_Fence(AP_InertialNav* inav);
AC_Fence(const AP_InertialNav* inav);
/// enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value
void enable(bool true_false) { _enabled = true_false; }
@ -89,7 +89,7 @@ private:
void clear_breach(uint8_t fence_type);
// pointers to other objects we depend upon
AP_InertialNav* _inav;
const AP_InertialNav *const _inav;
// parameters
AP_Int8 _enabled; // top level enable/disable control