mirror of https://github.com/ArduPilot/ardupilot
Attitude.pde - Removed rate limit based on SIM flights. These should never have been in place and seriously detriment Acro flight.
This commit is contained in:
parent
f274df454a
commit
1a5e2f4e37
|
@ -108,7 +108,6 @@ static int16_t
|
||||||
get_acro_roll(int32_t target_rate)
|
get_acro_roll(int32_t target_rate)
|
||||||
{
|
{
|
||||||
target_rate = target_rate * g.acro_p;
|
target_rate = target_rate * g.acro_p;
|
||||||
target_rate = constrain(target_rate, -10000, 10000);
|
|
||||||
return get_rate_roll(target_rate);
|
return get_rate_roll(target_rate);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -116,7 +115,6 @@ static int16_t
|
||||||
get_acro_pitch(int32_t target_rate)
|
get_acro_pitch(int32_t target_rate)
|
||||||
{
|
{
|
||||||
target_rate = target_rate * g.acro_p;
|
target_rate = target_rate * g.acro_p;
|
||||||
target_rate = constrain(target_rate, -10000, 10000);
|
|
||||||
return get_rate_pitch(target_rate);
|
return get_rate_pitch(target_rate);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -124,7 +122,6 @@ static int16_t
|
||||||
get_acro_yaw(int32_t target_rate)
|
get_acro_yaw(int32_t target_rate)
|
||||||
{
|
{
|
||||||
target_rate = g.pi_stabilize_yaw.get_p(target_rate);
|
target_rate = g.pi_stabilize_yaw.get_p(target_rate);
|
||||||
target_rate = constrain(target_rate, -15000, 15000);
|
|
||||||
return get_rate_yaw(target_rate);
|
return get_rate_yaw(target_rate);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue