mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: bug fix for simple_mode when run at 400hz
Mark radio frame as consumed so that simple mode does not apply the yaw correction more than once when run at very high rates (like 400hz on Pixhawk)
This commit is contained in:
parent
176a450ad2
commit
ac364c93dd
@ -1312,6 +1312,9 @@ void update_simple_mode(void)
|
||||
return;
|
||||
}
|
||||
|
||||
// mark radio frame as consumed
|
||||
ap.new_radio_frame = false;
|
||||
|
||||
if (ap.simple_mode == 1) {
|
||||
// rotate roll, pitch input by -initial simple heading (i.e. north facing)
|
||||
rollx = g.rc_1.control_in*simple_cos_yaw - g.rc_2.control_in*simple_sin_yaw;
|
||||
|
Loading…
Reference in New Issue
Block a user