Copter: RTL always land if in radio failsafe

Resolves issue in which vehicle would get stuck at RTL_ALT_FINAL if
failsafe occured.
Also clear out pilot acceleration from loiter controller if failsafe
occurs during the final descent.
This commit is contained in:
Randy Mackay 2014-04-25 14:36:45 +09:00
parent db51d37071
commit 05d9dc5cba
1 changed files with 7 additions and 3 deletions

View File

@ -32,7 +32,7 @@ static void rtl_run()
rtl_loiterathome_start();
break;
case LoiterAtHome:
if (g.rtl_alt_final > 0) {
if (g.rtl_alt_final > 0 && !failsafe.radio) {
rtl_descent_start();
}else{
rtl_land_start();
@ -260,11 +260,13 @@ static void rtl_descent_run()
update_simple_mode();
// process pilot's roll and pitch input
// To-Do: do we need to clear out feed forward if this is not called?
wp_nav.set_pilot_desired_acceleration(g.rc_1.control_in, g.rc_2.control_in);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs while descending
wp_nav.clear_pilot_desired_acceleration();
}
// run loiter controller
@ -317,11 +319,13 @@ static void rtl_land_run()
update_simple_mode();
// process pilot's roll and pitch input
// To-Do: do we need to clear out feed forward if this is not called?
wp_nav.set_pilot_desired_acceleration(g.rc_1.control_in, g.rc_2.control_in);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs while landing
wp_nav.clear_pilot_desired_acceleration();
}
// run loiter controller