diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index a6f8e20c2b..c0a3c52c91 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -820,7 +820,7 @@ bool AP_Arming_Copter::disarm() } #if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL - gcs().send_text(MAV_SEVERITY_INFO, "Disarming motors"); + gcs().send_text(MAV_SEVERITY_INFO, "NOTICE: Disarming motors"); #endif AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf(); diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 8b9c3f3f8e..d9172e61fe 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -822,12 +822,13 @@ void Copter::update_updownStatus2(uint8_t status) { copter.updownStatus = (UpDownState)status; if (status == 3) - { + { set_mode(Mode::Number::AUTO, ModeReason::REQUEST_CMD); mavlink_zr_flying_status_t zr_flying_status_t; zr_flying_status_t.updown_status = copter.updownStatus; zr_flying_status_t.countdown = 255; gcs().update_zr_fly_status(&zr_flying_status_t); + gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 执行继续任务"); } } diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 234b840376..47778e305f 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -102,7 +102,8 @@ void ModeRTL::run(bool disarm_on_land) } } else if (copter.updownStatus == UpDown_ContinueDescent) - { + { + gcs().send_text(MAV_SEVERITY_WARNING,"NOTICE: 开始着陆"); _state = RTL_Land; }