Fix for SIMPLE mode

This commit is contained in:
Jason Short 2012-01-14 11:32:48 -08:00
parent 72faa6525e
commit 0ae82da0fd

View File

@ -1460,7 +1460,7 @@ void update_roll_pitch_mode(void)
// new radio frame is used to make sure we only call this at 50hz
void update_simple_mode(void)
{
float simple_sin_y=0, simple_cos_x=0;
static float simple_sin_y=0, simple_cos_x=0;
// used to manage state machine
// which improves speed of function