Browse Source

更新起飞降落电池消息等级,消息添加前缀

master
yaozb 5 years ago
parent
commit
c1afedaf58
  1. 2
      ArduCopter/AP_Arming.cpp
  2. 4
      ArduCopter/mode_brake.cpp
  3. 4
      ArduCopter/mode_rtl.cpp
  4. 4
      libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp

2
ArduCopter/AP_Arming.cpp

@ -466,7 +466,7 @@ bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure) @@ -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;

4
ArduCopter/mode_brake.cpp

@ -87,10 +87,10 @@ void ModeBrake::run() @@ -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);
}

4
ArduCopter/mode_rtl.cpp

@ -91,10 +91,10 @@ void ModeRTL::run(bool disarm_on_land) @@ -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;
}

4
libraries/AP_BattMonitor/AP_BattMonitor_Serial_BattGo.cpp

@ -264,14 +264,14 @@ void AP_BattMonitor_Serial_BattGo::read() @@ -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;
}
}

Loading…
Cancel
Save