Browse Source

Copter: Correct yaw expo range limit

c415-sdk
Leonard Hall 4 years ago committed by Randy Mackay
parent
commit
300c5a9207
  1. 2
      ArduCopter/mode.cpp

2
ArduCopter/mode.cpp

@ -750,7 +750,7 @@ float Mode::get_pilot_desired_yaw_rate(int16_t stick_angle) @@ -750,7 +750,7 @@ float Mode::get_pilot_desired_yaw_rate(int16_t stick_angle)
}
// range check expo
g2.acro_y_expo = constrain_float(g2.acro_y_expo, 0.0f, 1.0f);
g2.acro_y_expo = constrain_float(g2.acro_y_expo, -0.5f, 1.0f);
// calculate yaw rate request
float yaw_request;

Loading…
Cancel
Save