Skip to content

Commit

Permalink
Plane: use deadzone in stick mixing
Browse files Browse the repository at this point in the history
this prevents small RC input deviations from impacting non-pilot
controlled modes via stick mixing
  • Loading branch information
tridge committed Oct 13, 2023
1 parent 0f5bbb2 commit ddf9598
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -259,7 +259,7 @@ void Plane::stabilize_stick_mixing_fbw()
// non-linear and ends up as 2x the maximum, to ensure that
// the user can direct the plane in any direction with stick
// mixing.
float roll_input = channel_roll->norm_input();
float roll_input = channel_roll->norm_input_dz();
if (roll_input > 0.5f) {
roll_input = (3*roll_input - 1);
} else if (roll_input < -0.5f) {
Expand All @@ -273,7 +273,7 @@ void Plane::stabilize_stick_mixing_fbw()
return;
}

float pitch_input = channel_pitch->norm_input();
float pitch_input = channel_pitch->norm_input_dz();
if (pitch_input > 0.5f) {
pitch_input = (3*pitch_input - 1);
} else if (pitch_input < -0.5f) {
Expand Down

0 comments on commit ddf9598

Please sign in to comment.