Skip to content

Commit

Permalink
AP_Motors: Heli dual: Constrain cyclic roll for intermeshing
Browse files Browse the repository at this point in the history
  • Loading branch information
MattKear authored and bnsgeyer committed Jun 9, 2024
1 parent 3ede599 commit 5784abd
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AP_Motors/AP_MotorsHeli_Dual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,7 +404,8 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c
pitch_out = _cyclic_max/4500.0f;
limit.pitch = true;
}
} else {
}
if (_dual_mode != AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE) {
if (roll_out < -_cyclic_max/4500.0f) {
roll_out = -_cyclic_max/4500.0f;
limit.roll = true;
Expand Down

0 comments on commit 5784abd

Please sign in to comment.