mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_Notify: Support all GPS status flags, with status >= GPS_OK_FIX_3D notified as having a lock
This commit is contained in:
parent
87c77dc07f
commit
64d4a1236f
@ -161,7 +161,7 @@ void AP_BoardLED::update(void)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 3:
|
default:
|
||||||
// solid blue on gps lock
|
// solid blue on gps lock
|
||||||
hal.gpio->write(HAL_GPIO_C_LED_PIN, HAL_GPIO_LED_ON);
|
hal.gpio->write(HAL_GPIO_C_LED_PIN, HAL_GPIO_LED_ON);
|
||||||
break;
|
break;
|
||||||
|
@ -33,7 +33,7 @@ public:
|
|||||||
/// notify_type - bitmask of notification types
|
/// notify_type - bitmask of notification types
|
||||||
struct notify_type {
|
struct notify_type {
|
||||||
uint16_t initialising : 1; // 1 if initialising and copter should not be moved
|
uint16_t initialising : 1; // 1 if initialising and copter should not be moved
|
||||||
uint16_t gps_status : 2; // 0 = no gps, 1 = no lock, 2 = 2d lock, 3 = 3d lock
|
uint16_t gps_status : 3; // 0 = no gps, 1 = no lock, 2 = 2d lock, 3 = 3d lock, 4 = dgps lock, 5 = rtk lock
|
||||||
uint16_t gps_glitching : 1; // 1 if gps position is not good
|
uint16_t gps_glitching : 1; // 1 if gps position is not good
|
||||||
uint16_t armed : 1; // 0 = disarmed, 1 = armed
|
uint16_t armed : 1; // 0 = disarmed, 1 = armed
|
||||||
uint16_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
uint16_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
||||||
|
@ -18,6 +18,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
#include <AP_GPS.h>
|
||||||
#include "ToshibaLED.h"
|
#include "ToshibaLED.h"
|
||||||
#include "AP_Notify.h"
|
#include "AP_Notify.h"
|
||||||
|
|
||||||
@ -167,7 +168,7 @@ void ToshibaLED::update_colours(void)
|
|||||||
// solid green or flashing green if armed
|
// solid green or flashing green if armed
|
||||||
if (AP_Notify::flags.armed) {
|
if (AP_Notify::flags.armed) {
|
||||||
// solid green if armed with GPS 3d lock
|
// solid green if armed with GPS 3d lock
|
||||||
if (AP_Notify::flags.gps_status == 3) {
|
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
_red_des = TOSHIBA_LED_OFF;
|
_red_des = TOSHIBA_LED_OFF;
|
||||||
_blue_des = TOSHIBA_LED_OFF;
|
_blue_des = TOSHIBA_LED_OFF;
|
||||||
_green_des = brightness;
|
_green_des = brightness;
|
||||||
@ -213,7 +214,7 @@ void ToshibaLED::update_colours(void)
|
|||||||
case 3:
|
case 3:
|
||||||
case 4:
|
case 4:
|
||||||
_red_des = TOSHIBA_LED_OFF;
|
_red_des = TOSHIBA_LED_OFF;
|
||||||
if (AP_Notify::flags.gps_status == 3) {
|
if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
// flashing green if disarmed with GPS 3d lock
|
// flashing green if disarmed with GPS 3d lock
|
||||||
_blue_des = TOSHIBA_LED_OFF;
|
_blue_des = TOSHIBA_LED_OFF;
|
||||||
_green_des = brightness;
|
_green_des = brightness;
|
||||||
|
Loading…
Reference in New Issue
Block a user