From 5f6e25b0374b24823fbe1763e02c0356e6e57567 Mon Sep 17 00:00:00 2001 From: zbr3550 Date: Sat, 8 Aug 2020 19:16:10 +0800 Subject: [PATCH] backup commit, rgbled close --- ArduCopter/Parameters.cpp | 8 ++++---- ArduCopter/version.h | 4 ++-- libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 8 +++++--- libraries/AP_Notify/RGBLed.cpp | 16 ++++++++++++++-- 4 files changed, 25 insertions(+), 11 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 2d7e3e556c..0faeee1c45 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1663,16 +1663,16 @@ const char* Copter::get_sysid_board_id(void) switch (type) { case 0: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.5 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2); break; case 1: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.5 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2); break; case 2: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.5 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2); break; case 3: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.5 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2); break; default: diff --git a/ArduCopter/version.h b/ArduCopter/version.h index 708a6f9cb0..45a66486ef 100644 --- a/ArduCopter/version.h +++ b/ArduCopter/version.h @@ -6,10 +6,10 @@ #include "ap_version.h" -#define THISFIRMWARE "ZRUAV v4.0.4-rc1.2" //"ArduCopter V4.0.0" +#define THISFIRMWARE "ZRUAV v4.0.5-rc1" //"ArduCopter V4.0.0" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,0,4,FIRMWARE_VERSION_TYPE_OFFICIAL +#define FIRMWARE_VERSION 4,0,5,FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_MAJOR 4 #define FW_MINOR 0 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index 8a6f22d6bc..4db442e0b1 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -266,7 +266,7 @@ void NavEKF2_core::setAidingMode() switch (PV_AidingMode) { case AID_NONE: // We have ceased aiding - gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u 停止协助",(unsigned)imu_index);//EKF2 IMU%u has stopped aiding + gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u 停止定位",(unsigned)imu_index);//EKF2 IMU%u has stopped aiding // When not aiding, estimate orientation & height fusing synthetic constant position and zero velocity measurement to constrain tilt errors posTimeout = true; velTimeout = true; @@ -285,7 +285,8 @@ void NavEKF2_core::setAidingMode() case AID_RELATIVE: // We have commenced aiding, but GPS usage has been prohibited so use optical flow only - gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using optical flow",(unsigned)imu_index); + // gcs().send_text(MAV_SEVERITY_INFO, "NOTICE:光流定位成功",(unsigned)imu_index); // EKF2 IMU%u is using optical flow + gcs().send_text(MAV_SEVERITY_INFO, "NOTICE:光流定位成功"); // EKF2 IMU%u is using optical flow posTimeout = true; velTimeout = true; // Reset the last valid flow measurement time @@ -300,7 +301,8 @@ void NavEKF2_core::setAidingMode() bool canUseExtNav = readyToUseExtNav(); // We have commenced aiding and GPS usage is allowed if (canUseGPS) { - gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using GPS",(unsigned)imu_index); + // gcs().send_text(MAV_SEVERITY_INFO, "NOTICE:GPS定位成功",(unsigned)imu_index); // EKF2 IMU%u is using GPS + gcs().send_text(MAV_SEVERITY_INFO, "NOTICE:GPS定位成功"); // EKF2 IMU%u is using GPS } posTimeout = false; velTimeout = false; diff --git a/libraries/AP_Notify/RGBLed.cpp b/libraries/AP_Notify/RGBLed.cpp index d520867cf5..1e8d7e4e49 100644 --- a/libraries/AP_Notify/RGBLed.cpp +++ b/libraries/AP_Notify/RGBLed.cpp @@ -215,7 +215,7 @@ void RGBLed::get_colour_ws2812(void) set_rgb_mode(1); return; } - + static uint16_t arm_delay_cnt; // solid green or blue if armed if (AP_Notify::flags.armed) { // solid green if armed with GPS 3d lock @@ -227,11 +227,23 @@ void RGBLed::get_colour_ws2812(void) } // solid blue if armed with no GPS lock // return sequence_armed_nogps; - _red_ws = _led_off; + else{ _red_ws = _led_off; _blue_ws = _led_medium; _green_ws = _led_medium; + set_rgb_mode(0);} + + if(arm_delay_cnt>500){ + _red_ws = _led_off; + _blue_ws = _led_off; + _green_ws = _led_off; set_rgb_mode(0); + }else{ + arm_delay_cnt+=1; + + } return; + }else{ + arm_delay_cnt = 0; } // double flash yellow if failing pre-arm checks