mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: fix init order of ekfYawReset_ms
This commit is contained in:
parent
317779f976
commit
cdd4570f02
@ -125,8 +125,7 @@ Copter::Copter(void) :
|
||||
#endif
|
||||
in_mavlink_delay(false),
|
||||
gcs_out_of_time(false),
|
||||
param_loader(var_info),
|
||||
ekfYawReset_ms(0)
|
||||
param_loader(var_info)
|
||||
{
|
||||
memset(¤t_loc, 0, sizeof(current_loc));
|
||||
|
||||
|
@ -208,7 +208,8 @@ private:
|
||||
// scale factor applied to velocity controller gain to prevent optical flow noise causing excessive angle demand noise
|
||||
float ekfNavVelGainScaler;
|
||||
|
||||
uint32_t ekfYawReset_ms;
|
||||
// system time in milliseconds of last recorded yaw reset from ekf
|
||||
uint32_t ekfYawReset_ms = 0;
|
||||
|
||||
// GCS selection
|
||||
AP_SerialManager serial_manager;
|
||||
|
Loading…
Reference in New Issue
Block a user