mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Copter: Loiter clears out pilot acceleration when failsafe occurs
This ensures invalid pilot desired accelerations are cleared from the loiter controller. This is probably not strictly necessary because the vehicle should switch out of Loiter and into RTL during failsafe.
This commit is contained in:
parent
05d9dc5cba
commit
20de5b3006
@ -45,7 +45,6 @@ static void loiter_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
|
||||
@ -61,6 +60,9 @@ static void loiter_run()
|
||||
// clear i term when we're taking off
|
||||
set_throttle_takeoff();
|
||||
}
|
||||
} else {
|
||||
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
|
||||
wp_nav.clear_pilot_desired_acceleration();
|
||||
}
|
||||
|
||||
// when landed reset targets and output zero throttle
|
||||
|
Loading…
Reference in New Issue
Block a user