|
|
@ -70,11 +70,8 @@ void ModeRTL::run(bool disarm_on_land) |
|
|
|
if (copter.updownStatus < UpDown_RequestDescent) |
|
|
|
if (copter.updownStatus < UpDown_RequestDescent) |
|
|
|
{ |
|
|
|
{ |
|
|
|
copter.updownStatus = UpDown_RequestDescent; |
|
|
|
copter.updownStatus = UpDown_RequestDescent; |
|
|
|
mavlink_zr_flying_status_t zr_flying_status_t; |
|
|
|
countdown = g.zr_rtl_delay;
|
|
|
|
zr_flying_status_t.updown_status = copter.updownStatus; |
|
|
|
gcs().send_message(MSG_ZR_FLYING_STATUS); |
|
|
|
countdown = g.zr_rtl_delay;
|
|
|
|
|
|
|
|
zr_flying_status_t.countdown = countdown;
|
|
|
|
|
|
|
|
gcs().update_zr_fly_status(&zr_flying_status_t); |
|
|
|
|
|
|
|
last_decent_time = AP_HAL::millis();
|
|
|
|
last_decent_time = AP_HAL::millis();
|
|
|
|
if(g.zr_rtl_delay>0){ |
|
|
|
if(g.zr_rtl_delay>0){ |
|
|
|
is_rtl_delay_enable = true; |
|
|
|
is_rtl_delay_enable = true; |
|
|
@ -86,16 +83,13 @@ void ModeRTL::run(bool disarm_on_land) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if((AP_HAL::millis()- last_decent_time)>=1000){ |
|
|
|
if((AP_HAL::millis()- last_decent_time)>=1000){ |
|
|
|
last_decent_time = AP_HAL::millis();
|
|
|
|
last_decent_time = AP_HAL::millis();
|
|
|
|
// mavlink_zr_flying_status_t zr_flying_status_t;
|
|
|
|
|
|
|
|
// zr_flying_status_t.updown_status = copter.updownStatus;
|
|
|
|
|
|
|
|
// zr_flying_status_t.countdown = countdown;
|
|
|
|
|
|
|
|
// gcs().update_zr_fly_status(&zr_flying_status_t);
|
|
|
|
|
|
|
|
if(countdown>0){ |
|
|
|
if(countdown>0){ |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO ,"NOTICE: 着陆倒计时(秒): %d",countdown); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO ,"NOTICE: 着陆倒计时(秒): %d",countdown); |
|
|
|
} |
|
|
|
} |
|
|
|
else if(countdown<=0){ |
|
|
|
else if(countdown<=0){ |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 开始着陆"); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 开始着陆"); |
|
|
|
copter.updownStatus = UpDown_ContinueDescent; |
|
|
|
copter.updownStatus = UpDown_ContinueDescent; |
|
|
|
|
|
|
|
gcs().send_message(MSG_ZR_FLYING_STATUS); |
|
|
|
_state = RTL_Land; |
|
|
|
_state = RTL_Land; |
|
|
|
} |
|
|
|
} |
|
|
|
countdown --; //TODO shiji countdown+1 s
|
|
|
|
countdown --; //TODO shiji countdown+1 s
|
|
|
@ -296,10 +290,7 @@ void ModeRTL::loiterathome_run() |
|
|
|
void ModeRTL::descent_start() |
|
|
|
void ModeRTL::descent_start() |
|
|
|
{ |
|
|
|
{ |
|
|
|
copter.updownStatus = UpDown_RTLDescent; |
|
|
|
copter.updownStatus = UpDown_RTLDescent; |
|
|
|
mavlink_zr_flying_status_t zr_flying_status_t; |
|
|
|
gcs().send_message(MSG_ZR_FLYING_STATUS); |
|
|
|
zr_flying_status_t.updown_status = copter.updownStatus; |
|
|
|
|
|
|
|
zr_flying_status_t.countdown = 255; |
|
|
|
|
|
|
|
gcs().update_zr_fly_status(&zr_flying_status_t); |
|
|
|
|
|
|
|
_state = RTL_FinalDescent; |
|
|
|
_state = RTL_FinalDescent; |
|
|
|
_state_complete = false; |
|
|
|
_state_complete = false; |
|
|
|
|
|
|
|
|
|
|
@ -439,13 +430,6 @@ void ModeRTL::land_run(bool disarm_on_land) |
|
|
|
|
|
|
|
|
|
|
|
land_run_horizontal_control(); |
|
|
|
land_run_horizontal_control(); |
|
|
|
land_run_vertical_control();
|
|
|
|
land_run_vertical_control();
|
|
|
|
|
|
|
|
|
|
|
|
if(AP_HAL::millis()-last_send_time>=500){ |
|
|
|
|
|
|
|
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); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void ModeRTL::build_path() |
|
|
|
void ModeRTL::build_path() |
|
|
|