HAL_SITL: fixed valgrind error in NOVA GPS
This commit is contained in:
parent
a4e0ecd368
commit
a611803b6d
@ -997,7 +997,7 @@ void SITL_State::_update_gps_nova(const struct gps_data *d, uint8_t instance)
|
|||||||
float cutoff;
|
float cutoff;
|
||||||
uint32_t svcount;
|
uint32_t svcount;
|
||||||
// extra data for individual prns
|
// extra data for individual prns
|
||||||
} psrdop;
|
} psrdop {};
|
||||||
|
|
||||||
struct PACKED bestpos
|
struct PACKED bestpos
|
||||||
{
|
{
|
||||||
@ -1023,7 +1023,7 @@ void SITL_State::_update_gps_nova(const struct gps_data *d, uint8_t instance)
|
|||||||
uint8_t extsolstat;
|
uint8_t extsolstat;
|
||||||
uint8_t galbeisigmask;
|
uint8_t galbeisigmask;
|
||||||
uint8_t gpsglosigmask;
|
uint8_t gpsglosigmask;
|
||||||
} bestpos;
|
} bestpos {};
|
||||||
|
|
||||||
struct PACKED bestvel
|
struct PACKED bestvel
|
||||||
{
|
{
|
||||||
@ -1036,7 +1036,7 @@ void SITL_State::_update_gps_nova(const struct gps_data *d, uint8_t instance)
|
|||||||
// + up
|
// + up
|
||||||
double vertspd;
|
double vertspd;
|
||||||
float resv;
|
float resv;
|
||||||
} bestvel;
|
} bestvel {};
|
||||||
|
|
||||||
uint16_t time_week;
|
uint16_t time_week;
|
||||||
uint32_t time_week_ms;
|
uint32_t time_week_ms;
|
||||||
|
Loading…
Reference in New Issue
Block a user