|
|
@ -144,8 +144,6 @@ void Copter::do_avoid_action(){ |
|
|
|
uint16_t rc10_in = RC_Channels::rc_channel(CH_6)->get_radio_in(); |
|
|
|
uint16_t rc10_in = RC_Channels::rc_channel(CH_6)->get_radio_in(); |
|
|
|
proxy_dist = (rc10_in - 1100)/900.0*50.0; |
|
|
|
proxy_dist = (rc10_in - 1100)/900.0*50.0; |
|
|
|
#else |
|
|
|
#else |
|
|
|
if(avoid.get_zr_mode() == 1){ |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
AP_Proximity *proximity = AP::proximity(); |
|
|
|
AP_Proximity *proximity = AP::proximity(); |
|
|
|
if(proximity == nullptr) |
|
|
|
if(proximity == nullptr) |
|
|
|
return; |
|
|
|
return; |
|
|
@ -153,11 +151,6 @@ void Copter::do_avoid_action(){ |
|
|
|
if(get_new_dist == false){ |
|
|
|
if(get_new_dist == false){ |
|
|
|
proxy_dist = avoid.get_zr_avd_max() + 1.0; |
|
|
|
proxy_dist = avoid.get_zr_avd_max() + 1.0; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
if(avoid.get_zr_mode() == 2){ |
|
|
|
|
|
|
|
uint16_t rc10_in = RC_Channels::rc_channel(CH_12)->get_radio_in(); |
|
|
|
|
|
|
|
proxy_dist = (rc10_in - 1100)/900.0*50.0; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
avoid_area_detect(proxy_dist); |
|
|
|
avoid_area_detect(proxy_dist); |
|
|
@ -214,7 +207,7 @@ void Copter::avoid_action(uint8_t area,uint8_t state,float dist) |
|
|
|
Vector3f pos_neu_cm; |
|
|
|
Vector3f pos_neu_cm; |
|
|
|
static int32_t max_climb_alt = 0; |
|
|
|
static int32_t max_climb_alt = 0; |
|
|
|
int32_t turn_yaw; |
|
|
|
int32_t turn_yaw; |
|
|
|
static uint32_t ctl_wait_time = AP_HAL::millis(); |
|
|
|
static uint32_t rtl_wait_time = AP_HAL::millis(); |
|
|
|
switch (action) |
|
|
|
switch (action) |
|
|
|
{ |
|
|
|
{ |
|
|
|
case PROXY_WAIT: |
|
|
|
case PROXY_WAIT: |
|
|
@ -281,7 +274,7 @@ void Copter::avoid_action(uint8_t area,uint8_t state,float dist) |
|
|
|
// mode_guided.set_destination(pos_neu_cm, false, 0, false, 0, false);
|
|
|
|
// mode_guided.set_destination(pos_neu_cm, false, 0, false, 0, false);
|
|
|
|
if(current_loc.alt > max_climb_alt){ |
|
|
|
if(current_loc.alt > max_climb_alt){ |
|
|
|
action = PROXY_NEED_CTL; |
|
|
|
action = PROXY_NEED_CTL; |
|
|
|
ctl_wait_time = AP_HAL::millis(); |
|
|
|
rtl_wait_time = AP_HAL::millis(); |
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"超出爬升高度限制:%.2f,请手动控制",current_loc.alt/100.0f); |
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"超出爬升高度限制:%.2f,请手动控制",current_loc.alt/100.0f); |
|
|
|
|
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
@ -323,13 +316,26 @@ void Copter::avoid_action(uint8_t area,uint8_t state,float dist) |
|
|
|
action = PROXY_WAIT; |
|
|
|
action = PROXY_WAIT; |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:人为控制,已离开障碍"); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:人为控制,已离开障碍"); |
|
|
|
} |
|
|
|
} |
|
|
|
if(tnow - ctl_wait_time > g.zr_avd_wait * 1000){ |
|
|
|
if(tnow - rtl_wait_time > (uint32_t)(g.zr_avd_wait * 1000)){ |
|
|
|
|
|
|
|
if(avoid.get_zr_mode() == 1){
|
|
|
|
action = PROXY_WAIT; |
|
|
|
action = PROXY_WAIT; |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:等待超时,原地降落"); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:等待超时,原地降落"); |
|
|
|
set_mode(Mode::Number::LAND,ModeReason::AVOIDANCE); |
|
|
|
set_mode(Mode::Number::LAND,ModeReason::AVOIDANCE); |
|
|
|
|
|
|
|
}else{ |
|
|
|
|
|
|
|
action = PROXY_RTL_ERR; |
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:等待超时,关闭避障返航"); |
|
|
|
|
|
|
|
set_mode(Mode::Number::RTL,ModeReason::AVOIDANCE); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
case PROXY_RTL_ERR: |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
if(control_mode == Mode::Number::LAND ){ // 如果切换到Land,则可以重新开始
|
|
|
|
|
|
|
|
action = PROXY_WAIT; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
default: |
|
|
|
default: |
|
|
|
break; |
|
|
|
break; |
|
|
|