Arducopter: Temp reversion to old Yaw controller.

This commit is contained in:
Jason Short 2012-07-14 12:26:13 -07:00
parent e3af0c7920
commit 44b16b7b61
1 changed files with 20 additions and 15 deletions

View File

@ -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