mirror of https://github.com/ArduPilot/ardupilot
get_acro_yaw added
This commit is contained in:
parent
19ab0f481e
commit
c64d781dce
|
@ -96,6 +96,14 @@ get_acro_pitch(int32_t target_rate)
|
||||||
return get_rate_pitch(target_rate);
|
return get_rate_pitch(target_rate);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static int
|
||||||
|
get_acro_yaw(int32_t 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);
|
||||||
|
}
|
||||||
|
|
||||||
static int
|
static int
|
||||||
get_rate_roll(int32_t target_rate)
|
get_rate_roll(int32_t target_rate)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue