From 4018c34930ea9384dba6b62f8e3351f727551e25 Mon Sep 17 00:00:00 2001 From: zbr Date: Fri, 17 Sep 2021 15:41:41 +0800 Subject: [PATCH] =?UTF-8?q?=E6=B5=8B=E8=AF=95=E5=85=88=E4=B8=8D=E7=94=A8Lo?= =?UTF-8?q?iter=E6=89=8B=E5=8A=A8=E9=81=BF=E9=9A=9C=EF=BC=8C=E4=B8=8D?= =?UTF-8?q?=E5=90=AF=E7=94=A8=E6=97=B6=E5=88=87=E6=8D=A2=E5=88=B0=E8=87=AA?= =?UTF-8?q?=E5=8A=A8=E9=81=BF=E9=9A=9C?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ArduCopter/UserCode.cpp | 4 ++++ ArduCopter/zr_flight.cpp | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduCopter/UserCode.cpp b/ArduCopter/UserCode.cpp index ae38a016c8..6f3d4bab8b 100644 --- a/ArduCopter/UserCode.cpp +++ b/ArduCopter/UserCode.cpp @@ -57,6 +57,10 @@ if(avoid.get_zr_mode() > 0 && (control_mode == Mode::Number::AUTO || control_mod if(far_from_home){ enable_avoid = true; } +}else if(control_mode == Mode::Number::LOITER && !avoid.get_avoid_action() ){ + if(far_from_home){ + enable_avoid = true; + } } if(last_flag != enable_avoid){ if(enable_avoid){ diff --git a/ArduCopter/zr_flight.cpp b/ArduCopter/zr_flight.cpp index 074e52f3b4..e6ce443f24 100644 --- a/ArduCopter/zr_flight.cpp +++ b/ArduCopter/zr_flight.cpp @@ -317,7 +317,7 @@ void Copter::avoid_action(uint8_t area,uint8_t state,float dist) gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:人为控制,已离开障碍"); } if(tnow - rtl_wait_time > (uint32_t)(g.zr_avd_wait * 1000)){ - if(avoid.get_zr_mode() == 1){ + if(avoid.get_zr_mode() == 2){ action = PROXY_WAIT; gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:等待超时,原地降落"); set_mode(Mode::Number::LAND,ModeReason::AVOIDANCE);