Browse Source

backup commit, rgbled close

master
zbr3550 5 years ago
parent
commit
5f6e25b037
  1. 8
      ArduCopter/Parameters.cpp
  2. 4
      ArduCopter/version.h
  3. 8
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
  4. 16
      libraries/AP_Notify/RGBLed.cpp

8
ArduCopter/Parameters.cpp

@ -1663,16 +1663,16 @@ const char* Copter::get_sysid_board_id(void) @@ -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:

4
ArduCopter/version.h

@ -6,10 +6,10 @@ @@ -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

8
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -266,7 +266,7 @@ void NavEKF2_core::setAidingMode() @@ -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() @@ -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() @@ -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;

16
libraries/AP_Notify/RGBLed.cpp

@ -215,7 +215,7 @@ void RGBLed::get_colour_ws2812(void) @@ -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) @@ -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

Loading…
Cancel
Save