mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Notify: Perform common checks first
This commit is contained in:
parent
66817e207f
commit
84ff78f5c6
@ -165,16 +165,13 @@ uint32_t RGBLed::get_colour_sequence(void) const
|
|||||||
if (!AP_Notify::flags.pre_arm_check) {
|
if (!AP_Notify::flags.pre_arm_check) {
|
||||||
return sequence_prearm_failing;
|
return sequence_prearm_failing;
|
||||||
}
|
}
|
||||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS &&
|
if (AP_Notify::flags.pre_arm_gps_check && good_ahrs_location) {
|
||||||
AP_Notify::flags.pre_arm_gps_check &&
|
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||||
good_ahrs_location) {
|
return sequence_disarmed_good_dgps_and_location;
|
||||||
return sequence_disarmed_good_dgps_and_location;
|
}
|
||||||
}
|
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
|
return sequence_disarmed_good_gps_and_location;
|
||||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D &&
|
}
|
||||||
AP_Notify::flags.pre_arm_gps_check &&
|
|
||||||
good_ahrs_location) {
|
|
||||||
return sequence_disarmed_good_gps_and_location;
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user