mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
ArduCopter: Bug fix, int8t should be uint16t.
This commit is contained in:
parent
e9058df31f
commit
d7ba808400
@ -85,7 +85,7 @@ static struct {
|
||||
Vector2f wind_comp_ef; // wind compensation in earth frame, filtered lean angles from position controller
|
||||
int16_t wind_comp_roll; // roll angle to compensate for wind
|
||||
int16_t wind_comp_pitch; // pitch angle to compensate for wind
|
||||
int8_t wind_comp_start_timer; // counter to delay start of wind compensation for a short time after loiter is engaged
|
||||
uint16_t wind_comp_start_timer; // counter to delay start of wind compensation for a short time after loiter is engaged
|
||||
int8_t wind_comp_timer; // counter to reduce wind comp roll/pitch lean angle calcs to 10hz
|
||||
|
||||
// final output
|
||||
|
Loading…
Reference in New Issue
Block a user