mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Arming: Add GPS configuration checks to arming
This commit is contained in:
parent
4251ee0e4b
commit
18f55eccea
@ -38,8 +38,8 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
|
||||
// @Param: CHECK
|
||||
// @DisplayName: Arm Checks to Peform (bitmask)
|
||||
// @Description: Checks prior to arming motor. This is a bitmask of checks that will be performed befor allowing arming. The default is no checks, allowing arming at any time. You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72. For most users it is recommended that you set this to 1 to enable all checks.
|
||||
// @Values: 0:None,1:All,2:Barometer,4:Compass,8:GPS,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Failsafe,128:Board voltage,256:Battery Level,512:Airspeed,1024:LoggingAvailable,2048:Hardware safety switch
|
||||
// @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS,4:INS,5:Parameters,6:RC,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch
|
||||
// @Values: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Failsafe,128:Board voltage,256:Battery Level,512:Airspeed,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration
|
||||
// @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("CHECK", 2, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
|
||||
|
||||
@ -305,9 +305,8 @@ bool AP_Arming::compass_checks(bool report)
|
||||
|
||||
bool AP_Arming::gps_checks(bool report)
|
||||
{
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
(checks_to_perform & ARMING_CHECK_GPS)) {
|
||||
const AP_GPS &gps = ahrs.get_gps();
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {
|
||||
|
||||
//GPS OK?
|
||||
if (home_is_set == HOME_UNSET ||
|
||||
@ -319,6 +318,17 @@ bool AP_Arming::gps_checks(bool report)
|
||||
}
|
||||
}
|
||||
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
|
||||
uint8_t first_unconfigured = gps.first_unconfigured_gps();
|
||||
if (first_unconfigured != AP_GPS::GPS_ALL_CONFIGURED) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,
|
||||
"PreArm: GPS %d has not been fully configured",
|
||||
first_unconfigured);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -24,6 +24,7 @@ public:
|
||||
ARMING_CHECK_AIRSPEED = 0x0200,
|
||||
ARMING_CHECK_LOGGING = 0x0400,
|
||||
ARMING_CHECK_SWITCH = 0x0800,
|
||||
ARMING_CHECK_GPS_CONFIG = 0x1600,
|
||||
};
|
||||
|
||||
enum ArmingMethod {
|
||||
|
Loading…
Reference in New Issue
Block a user