diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 9572aa8a03..a6f8e20c2b 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -466,7 +466,7 @@ bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure) { check_failed(true, "无法解锁,授权码错误!"); }else{ - check_failed(true, "无法解锁,授权于%d-%d-%d到期!", deadline / 10000, (deadline % 10000) / 100, deadline % 100); + check_failed(true, "无法解锁,授权于%ld-%ld-%ld到期!", deadline / 10000, (deadline % 10000) / 100, deadline % 100); } // check_failed(display_failure, "Trial time has expired at %d-%d-%d !", deadline / 10000, (deadline % 10000) / 100, deadline % 100); return false; diff --git a/ArduCopter/mode_brake.cpp b/ArduCopter/mode_brake.cpp index 9c0e5a6a66..01e2f83e4b 100644 --- a/ArduCopter/mode_brake.cpp +++ b/ArduCopter/mode_brake.cpp @@ -87,10 +87,10 @@ void ModeBrake::run() // zr_flying_status_t.countdown = countdown; // gcs().update_zr_fly_status(&zr_flying_status_t); if(countdown>0){ - gcs().send_text(MAV_SEVERITY_INFO,"继续任务倒计时(秒):%d",countdown); + gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 继续任务倒计时(秒):%d",countdown); } else if(countdown<=0){ - gcs().send_text(MAV_SEVERITY_INFO," 执行继续任务"); + gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 执行继续任务"); copter.updownStatus = UpDown_ContinueClimb; set_mode(Mode::Number::AUTO, ModeReason::REQUEST_CMD); } diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 929a998264..234b840376 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -91,10 +91,10 @@ void ModeRTL::run(bool disarm_on_land) // zr_flying_status_t.countdown = countdown; // gcs().update_zr_fly_status(&zr_flying_status_t); if(countdown>0){ - gcs().send_text(MAV_SEVERITY_INFO,"着陆倒计时(秒): %d",countdown); + gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 着陆倒计时(秒): %d",countdown); } else if(countdown<=0){ - gcs().send_text(MAV_SEVERITY_INFO,"开始着陆"); + gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 开始着陆"); copter.updownStatus = UpDown_ContinueDescent; _state = RTL_Land; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp index 0cd7dbb18d..004f8bf732 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp @@ -264,14 +264,14 @@ void AP_BattMonitor_Serial_BattGo::read() }else{ if(tnow-last_rev_batt_time>5000000 && tnow - last_prt > 20000000 ){ _interim_state.healthy = false; - gcs().send_text(MAV_SEVERITY_INFO,"BATT_ERR:已经%d秒没有接收到智能电池 的串口数据!",(tnow-last_rev_batt_time)/1000000); + gcs().send_text(MAV_SEVERITY_WARNING,"BATT_ERR:已经%d秒没有接收到智能电池的串口数据!",(tnow-last_rev_batt_time)/1000000); last_prt = tnow; } } }else{ if(tnow-last_rev_batt_time>5000000 && tnow - last_prt > 20000000 ){ _interim_state.healthy = false; - gcs().send_text(MAV_SEVERITY_INFO,"BATT_ERR:已经%d秒没有接收到智能电池 的串口数据!",(tnow-last_rev_batt_time)/1000000); + gcs().send_text(MAV_SEVERITY_WARNING,"BATT_ERR:已经%d秒没有接收到智能电池的串口数据!",(tnow-last_rev_batt_time)/1000000); last_prt = tnow; } }