|
|
@ -72,21 +72,20 @@ void ModeRTL::run(bool disarm_on_land) |
|
|
|
copter.updownStatus = UpDown_RequestDescent; |
|
|
|
copter.updownStatus = UpDown_RequestDescent; |
|
|
|
mavlink_zr_flying_status_t zr_flying_status_t; |
|
|
|
mavlink_zr_flying_status_t zr_flying_status_t; |
|
|
|
zr_flying_status_t.updown_status = copter.updownStatus; |
|
|
|
zr_flying_status_t.updown_status = copter.updownStatus; |
|
|
|
countdown = g.updown_countdown;
|
|
|
|
countdown = g.zr_rtl_delay;
|
|
|
|
zr_flying_status_t.countdown = countdown;
|
|
|
|
zr_flying_status_t.countdown = countdown;
|
|
|
|
gcs().update_zr_fly_status(&zr_flying_status_t); |
|
|
|
gcs().update_zr_fly_status(&zr_flying_status_t); |
|
|
|
last_decent_time = AP_HAL::millis();
|
|
|
|
last_decent_time = AP_HAL::millis();
|
|
|
|
if(g.updown_countdown>0){ |
|
|
|
if(g.zr_rtl_delay>0){ |
|
|
|
is_countdown_enable = true; |
|
|
|
is_rtl_delay_enable = true; |
|
|
|
}else{ |
|
|
|
}else{ |
|
|
|
is_countdown_enable = false; |
|
|
|
is_rtl_delay_enable = false; |
|
|
|
}
|
|
|
|
}
|
|
|
|
} |
|
|
|
} |
|
|
|
else if(copter.updownStatus ==UpDown_RequestDescent&&is_countdown_enable) |
|
|
|
else if(copter.updownStatus ==UpDown_RequestDescent&&is_rtl_delay_enable) |
|
|
|
{ |
|
|
|
{ |
|
|
|
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();
|
|
|
|
countdown --; |
|
|
|
|
|
|
|
// mavlink_zr_flying_status_t zr_flying_status_t;
|
|
|
|
// mavlink_zr_flying_status_t zr_flying_status_t;
|
|
|
|
// zr_flying_status_t.updown_status = copter.updownStatus;
|
|
|
|
// zr_flying_status_t.updown_status = copter.updownStatus;
|
|
|
|
// zr_flying_status_t.countdown = countdown;
|
|
|
|
// zr_flying_status_t.countdown = countdown;
|
|
|
@ -99,6 +98,7 @@ void ModeRTL::run(bool disarm_on_land) |
|
|
|
copter.updownStatus = UpDown_ContinueDescent; |
|
|
|
copter.updownStatus = UpDown_ContinueDescent; |
|
|
|
_state = RTL_Land; |
|
|
|
_state = RTL_Land; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
countdown --; //TODO shiji countdown+1 s
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
else if (copter.updownStatus == UpDown_ContinueDescent) |
|
|
|
else if (copter.updownStatus == UpDown_ContinueDescent) |
|
|
|