Browse Source

添加消息汉化,更改倒计时等级

mission-4.1.18
yaozb 5 years ago
parent
commit
c6b43b7eef
  1. 4
      ArduCopter/mode_brake.cpp
  2. 4
      ArduCopter/mode_rtl.cpp
  3. 4
      libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp
  4. 2
      libraries/GCS_MAVLink/MissionItemProtocol.cpp

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_WARNING,"NOTICE: 继续任务倒计时(秒):%d",countdown);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 继续任务倒计时(秒):%d",countdown);
}
else if(countdown<=0){
gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 执行继续任务");
gcs().send_text(MAV_SEVERITY_INFO,"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_WARNING,"NOTICE: 着陆倒计时(秒): %d",countdown);
gcs().send_text(MAV_SEVERITY_INFO ,"NOTICE: 着陆倒计时(秒): %d",countdown);
}
else if(countdown<=0){
gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 开始着陆");
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 开始着陆");
copter.updownStatus = UpDown_ContinueDescent;
_state = RTL_Land;
}

4
libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp

@ -637,10 +637,10 @@ void AP_Frsky_Telem::check_sensor_status_flags(void) @@ -637,10 +637,10 @@ void AP_Frsky_Telem::check_sensor_status_flags(void)
queue_message(MAV_SEVERITY_CRITICAL, "Geofence Breach");
check_sensor_status_timer = now;
} else if ((_sensor_status_flags & MAV_SYS_STATUS_AHRS) > 0) {
queue_message(MAV_SEVERITY_CRITICAL, "Bad AHRS");
queue_message(MAV_SEVERITY_CRITICAL, "姿态不佳");//Bad AHRS
check_sensor_status_timer = now;
} else if ((_sensor_status_flags & MAV_SYS_STATUS_SENSOR_RC_RECEIVER) > 0) {
queue_message(MAV_SEVERITY_CRITICAL, "No RC Receiver");
queue_message(MAV_SEVERITY_CRITICAL, "未接收到遥控器信号");//No RC Receiver
check_sensor_status_timer = now;
} else if ((_sensor_status_flags & MAV_SYS_STATUS_LOGGING) > 0) {
queue_message(MAV_SEVERITY_CRITICAL, "Bad Logging");

2
libraries/GCS_MAVLink/MissionItemProtocol.cpp

@ -40,7 +40,7 @@ bool MissionItemProtocol::mavlink2_requirement_met(const GCS_MAVLINK &_link, con @@ -40,7 +40,7 @@ bool MissionItemProtocol::mavlink2_requirement_met(const GCS_MAVLINK &_link, con
if (!_link.sending_mavlink1()) {
return true;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Need mavlink2 for item transfer");//Need mavlink2 for item transfer
gcs().send_text(MAV_SEVERITY_WARNING, "需要mavlink2进行消息转换");//Need mavlink2 for item transfer
send_mission_ack(_link, msg, MAV_MISSION_UNSUPPORTED);
return false;
}

Loading…
Cancel
Save