mirror of https://github.com/ArduPilot/ardupilot
Arducopter: Temp reversion to old Yaw controller.
This commit is contained in:
parent
e3af0c7920
commit
44b16b7b61
|
@ -129,6 +129,13 @@ get_acro_pitch(int32_t target_rate)
|
|||
|
||||
static int16_t
|
||||
get_acro_yaw(int32_t target_rate)
|
||||
{
|
||||
target_rate = g.pi_stabilize_yaw.get_p(target_rate);
|
||||
return get_rate_yaw(target_rate);
|
||||
}
|
||||
|
||||
static int16_t
|
||||
get_acro_yaw2(int32_t target_rate)
|
||||
{
|
||||
static int32_t last_target_rate = 0; // last iteration's target rate
|
||||
int32_t p,i,d; // used to capture pid values for logging
|
||||
|
@ -197,8 +204,6 @@ get_acro_yaw(int32_t target_rate)
|
|||
#endif
|
||||
|
||||
return output;
|
||||
|
||||
|
||||
}
|
||||
|
||||
static int16_t
|
||||
|
|
Loading…
Reference in New Issue