mirror of https://github.com/ArduPilot/ardupilot
Fix for SIMPLE mode
This commit is contained in:
parent
6714ab49ad
commit
cf51967bbb
|
@ -1460,7 +1460,7 @@ void update_roll_pitch_mode(void)
|
||||||
// new radio frame is used to make sure we only call this at 50hz
|
// new radio frame is used to make sure we only call this at 50hz
|
||||||
void update_simple_mode(void)
|
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
|
// used to manage state machine
|
||||||
// which improves speed of function
|
// which improves speed of function
|
||||||
|
|
Loading…
Reference in New Issue