AC_Fence: change inav to const reference

This commit is contained in:
Jonathan Challinger 2015-04-13 15:07:40 -07:00 committed by Randy Mackay
parent fddaca4cf7
commit f06cc5d0c1
2 changed files with 5 additions and 5 deletions

View File

@ -55,7 +55,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] PROGMEM = {
};
/// Default constructor.
AC_Fence::AC_Fence(const AP_InertialNav* inav) :
AC_Fence::AC_Fence(const AP_InertialNav& inav) :
_inav(inav),
_alt_max_backup(0),
_circle_radius_backup(0),
@ -102,7 +102,7 @@ bool AC_Fence::pre_arm_check() const
}
// if we have horizontal limits enabled, check inertial nav position is ok
if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE)!=0 && !_inav->get_filter_status().flags.horiz_pos_abs && !_inav->get_filter_status().flags.pred_horiz_pos_abs) {
if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE)!=0 && !_inav.get_filter_status().flags.horiz_pos_abs && !_inav.get_filter_status().flags.pred_horiz_pos_abs) {
return false;
}
@ -132,7 +132,7 @@ uint8_t AC_Fence::check_fence()
}
// get current altitude in meters
float curr_alt = _inav->get_altitude() * 0.01f;
float curr_alt = _inav.get_altitude() * 0.01f;
// altitude fence check
if ((_enabled_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {

View File

@ -33,7 +33,7 @@ class AC_Fence
public:
/// Constructor
AC_Fence(const 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; }
@ -95,7 +95,7 @@ private:
void clear_breach(uint8_t fence_type);
// pointers to other objects we depend upon
const AP_InertialNav *const _inav;
const AP_InertialNav& _inav;
// parameters
AP_Int8 _enabled; // top level enable/disable control