mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_Limits/AP_Limit_GPSLock.cpp
This commit is contained in:
parent
065cdfe7d0
commit
406eb1430c
|
@ -10,37 +10,37 @@
|
||||||
#include <AP_Limit_GPSLock.h>
|
#include <AP_Limit_GPSLock.h>
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_Limit_GPSLock::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AP_Limit_GPSLock::var_info[] PROGMEM = {
|
||||||
// @Param: GPSLCK_ON
|
// @Param: GPSLCK_ON
|
||||||
// @DisplayName: Enable gpslock
|
// @DisplayName: Enable gpslock
|
||||||
// @Description: Setting this to Enabled(1) will enable the gpslock. Setting this to Disabled(0) will disable the gpslock
|
// @Description: Setting this to Enabled(1) will enable the gpslock. Setting this to Disabled(0) will disable the gpslock
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GPSLCK_ON", 0, AP_Limit_GPSLock, _enabled, 0),
|
AP_GROUPINFO("GPSLCK_ON", 0, AP_Limit_GPSLock, _enabled, 0),
|
||||||
|
|
||||||
// @Param: GPSLCK_REQ
|
// @Param: GPSLCK_REQ
|
||||||
// @DisplayName: Require gpslock
|
// @DisplayName: Require gpslock
|
||||||
// @Description: Setting this to Enabled(1) will make being inside the gpslock a required check before arming the vehicle.
|
// @Description: Setting this to Enabled(1) will make being inside the gpslock a required check before arming the vehicle.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GPSLCK_REQ", 1, AP_Limit_GPSLock, _required, 0),
|
AP_GROUPINFO("GPSLCK_REQ", 1, AP_Limit_GPSLock, _required, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Limit_GPSLock::AP_Limit_GPSLock(GPS *&gps) :
|
AP_Limit_GPSLock::AP_Limit_GPSLock(GPS *&gps) :
|
||||||
AP_Limit_Module(AP_LIMITS_GPSLOCK), // enabled and required
|
AP_Limit_Module(AP_LIMITS_GPSLOCK), // enabled and required
|
||||||
_gps(gps)
|
_gps(gps)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
bool AP_Limit_GPSLock::triggered() {
|
bool AP_Limit_GPSLock::triggered() {
|
||||||
_triggered = false; // reset trigger before checking
|
_triggered = false; // reset trigger before checking
|
||||||
|
|
||||||
if (!_gps || !_gps->fix) {
|
if (!_gps || !_gps->fix) {
|
||||||
_triggered = true;
|
_triggered = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
return _triggered;
|
return _triggered;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue