mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM-simple: don't use uninitialised simple trig values
This commit is contained in:
parent
782fbc2d38
commit
9ee3431928
@ -1419,7 +1419,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, simple_cos_x;
|
||||
float simple_sin_y=0, simple_cos_x=0;
|
||||
|
||||
// used to manage state machine
|
||||
// which improves speed of function
|
||||
|
Loading…
Reference in New Issue
Block a user