Copter: range check ACRO_EXPO to be no more than 1
This commit is contained in:
parent
7202aa00da
commit
a31f30e6bd
@ -59,6 +59,11 @@ static void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int
|
|||||||
// expo variables
|
// expo variables
|
||||||
float rp_in, rp_in3, rp_out;
|
float rp_in, rp_in3, rp_out;
|
||||||
|
|
||||||
|
// range check expo
|
||||||
|
if (g.acro_expo > 1.0f) {
|
||||||
|
g.acro_expo = 1.0f;
|
||||||
|
}
|
||||||
|
|
||||||
// roll expo
|
// roll expo
|
||||||
rp_in = float(roll_in)/ROLL_PITCH_INPUT_MAX;
|
rp_in = float(roll_in)/ROLL_PITCH_INPUT_MAX;
|
||||||
rp_in3 = rp_in*rp_in*rp_in;
|
rp_in3 = rp_in*rp_in*rp_in;
|
||||||
|
Loading…
Reference in New Issue
Block a user