Browse Source

Plane: fixed use of expo values in radio

backport of https://github.com/ArduPilot/ardupilot/pull/19751
zr-v5.1
Andrew Tridgell 3 years ago committed by Randy Mackay
parent
commit
b63ca21a5e
  1. 4
      ArduPlane/radio.cpp

4
ArduPlane/radio.cpp

@ -410,10 +410,10 @@ float Plane::roll_in_expo(bool use_dz) const @@ -410,10 +410,10 @@ float Plane::roll_in_expo(bool use_dz) const
float Plane::pitch_in_expo(bool use_dz) const
{
return channel_expo(channel_pitch, g2.man_expo_roll, use_dz);
return channel_expo(channel_pitch, g2.man_expo_pitch, use_dz);
}
float Plane::rudder_in_expo(bool use_dz) const
{
return channel_expo(channel_rudder, g2.man_expo_roll, use_dz);
return channel_expo(channel_rudder, g2.man_expo_rudder, use_dz);
}

Loading…
Cancel
Save