mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: ACRO bug fix from Jason
This commit is contained in:
parent
3633ccb5bd
commit
0015747af9
@ -129,7 +129,7 @@ get_roll_rate_stabilized_ef(int32_t stick_angle)
|
|||||||
roll_axis = wrap_180(roll_axis);
|
roll_axis = wrap_180(roll_axis);
|
||||||
|
|
||||||
// ensure that we don't reach gimbal lock
|
// ensure that we don't reach gimbal lock
|
||||||
if (labs(roll_axis > 4500) && g.acro_trainer_enabled) {
|
if (labs(roll_axis) > 4500 && g.acro_trainer_enabled) {
|
||||||
roll_axis = constrain(roll_axis, -4500, 4500);
|
roll_axis = constrain(roll_axis, -4500, 4500);
|
||||||
angle_error = wrap_180(roll_axis - ahrs.roll_sensor);
|
angle_error = wrap_180(roll_axis - ahrs.roll_sensor);
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user