mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: use zero length flexible arrays
this works with gcc-6.1 and also works with asan. Hopefully it will make coverity happy too.
This commit is contained in:
parent
741fe9464e
commit
af116d238f
|
@ -90,7 +90,7 @@ private:
|
|||
erb_stat stat;
|
||||
erb_dops dops;
|
||||
erb_vel vel;
|
||||
uint8_t bytes[1];
|
||||
uint8_t bytes[0];
|
||||
} _buffer;
|
||||
|
||||
enum erb_protocol_bytes {
|
||||
|
|
|
@ -72,7 +72,7 @@ private:
|
|||
// Receive buffer
|
||||
union PACKED {
|
||||
diyd_mtk_msg msg;
|
||||
uint8_t bytes[1];
|
||||
uint8_t bytes[0];
|
||||
} _buffer;
|
||||
|
||||
// Buffer parse & GPS state update
|
||||
|
|
|
@ -78,6 +78,6 @@ private:
|
|||
// Receive buffer
|
||||
union {
|
||||
diyd_mtk_msg msg;
|
||||
uint8_t bytes[1];
|
||||
uint8_t bytes[0];
|
||||
} _buffer;
|
||||
};
|
||||
|
|
|
@ -98,7 +98,7 @@ private:
|
|||
// Message buffer
|
||||
union {
|
||||
sirf_geonav nav;
|
||||
uint8_t bytes[1];
|
||||
uint8_t bytes[0];
|
||||
} _buffer;
|
||||
|
||||
bool _parse_gps(void);
|
||||
|
|
|
@ -384,7 +384,7 @@ private:
|
|||
ubx_rxm_rawx rxm_rawx;
|
||||
#endif
|
||||
ubx_ack_ack ack;
|
||||
uint8_t bytes[1];
|
||||
uint8_t bytes[0];
|
||||
} _buffer;
|
||||
|
||||
enum ubs_protocol_bytes {
|
||||
|
|
Loading…
Reference in New Issue