mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Notify: add pre_arm_gps_check flag
RGB LED will remain flashing blue when vehicle is disarmed and this check has failed (i.e. false).
This commit is contained in:
parent
e757d75f54
commit
d67b4a8d49
@ -56,6 +56,7 @@ public:
|
||||
uint16_t baro_glitching : 1; // 1 if baro altitude is not good
|
||||
uint16_t armed : 1; // 0 = disarmed, 1 = armed
|
||||
uint16_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
||||
uint16_t pre_arm_gps_check : 1; // 0 = failing pre-arm GPS checks, 1 = passed
|
||||
uint16_t arming_failed : 1; // 1 if copter failed to arm after user input
|
||||
uint16_t save_trim : 1; // 1 if gathering trim data
|
||||
uint16_t esc_calibration : 1; // 1 if calibrating escs
|
||||
|
@ -194,7 +194,7 @@ void RGBLed::update_colours(void)
|
||||
return;
|
||||
}
|
||||
|
||||
// solid green or flashing green if armed
|
||||
// solid green or blue if armed
|
||||
if (AP_Notify::flags.armed) {
|
||||
// solid green if armed with GPS 3d lock
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
@ -234,32 +234,34 @@ void RGBLed::update_colours(void)
|
||||
break;
|
||||
}
|
||||
}else{
|
||||
// flashing green if disarmed with GPS 3d lock
|
||||
// flashing blue if disarmed with no gps lock
|
||||
// fast flashing green if disarmed with GPS 3D lock and DGPS
|
||||
// slow flashing green if disarmed with GPS 3d lock (and no DGPS)
|
||||
// flashing blue if disarmed with no gps lock or gps pre_arm checks have failed
|
||||
bool fast_green = AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS && AP_Notify::flags.pre_arm_gps_check;
|
||||
switch(step) {
|
||||
case 0:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = brightness;
|
||||
}
|
||||
break;
|
||||
case 1:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = _led_off;
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = brightness;
|
||||
}
|
||||
break;
|
||||
case 3:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = _led_off;
|
||||
}
|
||||
break;
|
||||
case 4:
|
||||
_red_des = _led_off;
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D && AP_Notify::flags.pre_arm_gps_check) {
|
||||
// flashing green if disarmed with GPS 3d lock
|
||||
_blue_des = _led_off;
|
||||
_green_des = brightness;
|
||||
@ -270,24 +272,24 @@ void RGBLed::update_colours(void)
|
||||
}
|
||||
break;
|
||||
case 5:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = _led_off;
|
||||
}
|
||||
break;
|
||||
|
||||
case 6:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = brightness;
|
||||
}
|
||||
break;
|
||||
|
||||
case 7:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = _led_off;
|
||||
}
|
||||
break;
|
||||
case 8:
|
||||
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) {
|
||||
if (fast_green) {
|
||||
_green_des = brightness;
|
||||
}
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user