mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AC_Fence: make member pointer to AP_InertialNav const, remove unused
gps-pointer member
This commit is contained in:
parent
7564cc02af
commit
596c7a25b7
@ -55,7 +55,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] PROGMEM = {
|
|||||||
};
|
};
|
||||||
|
|
||||||
/// Default constructor.
|
/// Default constructor.
|
||||||
AC_Fence::AC_Fence(AP_InertialNav* inav) :
|
AC_Fence::AC_Fence(const AP_InertialNav* inav) :
|
||||||
_inav(inav),
|
_inav(inav),
|
||||||
_alt_max_backup(0),
|
_alt_max_backup(0),
|
||||||
_circle_radius_backup(0),
|
_circle_radius_backup(0),
|
||||||
|
@ -32,7 +32,7 @@ class AC_Fence
|
|||||||
public:
|
public:
|
||||||
|
|
||||||
/// Constructor
|
/// 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
|
/// enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value
|
||||||
void enable(bool true_false) { _enabled = true_false; }
|
void enable(bool true_false) { _enabled = true_false; }
|
||||||
@ -89,7 +89,7 @@ private:
|
|||||||
void clear_breach(uint8_t fence_type);
|
void clear_breach(uint8_t fence_type);
|
||||||
|
|
||||||
// pointers to other objects we depend upon
|
// pointers to other objects we depend upon
|
||||||
AP_InertialNav* _inav;
|
const AP_InertialNav *const _inav;
|
||||||
|
|
||||||
// parameters
|
// parameters
|
||||||
AP_Int8 _enabled; // top level enable/disable control
|
AP_Int8 _enabled; // top level enable/disable control
|
||||||
|
Loading…
Reference in New Issue
Block a user