mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: do not use flexible array in union
We actually don't want a flexible array in this union, but rather a way to access it byte by byte. This fixes the build for gcc >= 6 In file included from ../../libraries/AP_GPS/AP_GPS.cpp:24:0: ../../libraries/AP_GPS/AP_GPS_ERB.h:93:23: error: flexible array member in union uint8_t bytes[]; ^ compilation terminated due to -Wfatal-errors. In file included from ../../libraries/AP_GPS/AP_GPS_ERB.cpp:22:0: ../../libraries/AP_GPS/AP_GPS_ERB.h:93:23: error: flexible array member in union uint8_t bytes[]; ^ compilation terminated due to -Wfatal-errors. In file included from ../../libraries/AP_GPS/AP_GPS_MTK.cpp:25:0: ../../libraries/AP_GPS/AP_GPS_MTK.h:75:23: error: flexible array member in union uint8_t bytes[]; ^ compilation terminated due to -Wfatal-errors. In file included from ../../libraries/AP_GPS/AP_GPS_MTK19.cpp:26:0: ../../libraries/AP_GPS/AP_GPS_MTK.h:75:23: error: flexible array member in union uint8_t bytes[]; ^ compilation terminated due to -Wfatal-errors. In file included from ../../libraries/AP_GPS/AP_GPS_SIRF.cpp:22:0: ../../libraries/AP_GPS/AP_GPS_SIRF.h:101:23: error: flexible array member in union uint8_t bytes[]; ^ compilation terminated due to -Wfatal-errors. In file included from ../../libraries/AP_GPS/AP_GPS_UBLOX.cpp:23:0: ../../libraries/AP_GPS/AP_GPS_UBLOX.h:387:23: error: flexible array member in union uint8_t bytes[]; ^ compilation terminated due to -Wfatal-errors.
This commit is contained in:
parent
d615628367
commit
39bd196481
@ -90,7 +90,7 @@ private:
|
|||||||
erb_stat stat;
|
erb_stat stat;
|
||||||
erb_dops dops;
|
erb_dops dops;
|
||||||
erb_vel vel;
|
erb_vel vel;
|
||||||
uint8_t bytes[];
|
uint8_t bytes[1];
|
||||||
} _buffer;
|
} _buffer;
|
||||||
|
|
||||||
enum erb_protocol_bytes {
|
enum erb_protocol_bytes {
|
||||||
|
@ -72,7 +72,7 @@ private:
|
|||||||
// Receive buffer
|
// Receive buffer
|
||||||
union PACKED {
|
union PACKED {
|
||||||
diyd_mtk_msg msg;
|
diyd_mtk_msg msg;
|
||||||
uint8_t bytes[];
|
uint8_t bytes[1];
|
||||||
} _buffer;
|
} _buffer;
|
||||||
|
|
||||||
// Buffer parse & GPS state update
|
// Buffer parse & GPS state update
|
||||||
|
@ -78,6 +78,6 @@ private:
|
|||||||
// Receive buffer
|
// Receive buffer
|
||||||
union {
|
union {
|
||||||
diyd_mtk_msg msg;
|
diyd_mtk_msg msg;
|
||||||
uint8_t bytes[];
|
uint8_t bytes[1];
|
||||||
} _buffer;
|
} _buffer;
|
||||||
};
|
};
|
||||||
|
@ -98,7 +98,7 @@ private:
|
|||||||
// Message buffer
|
// Message buffer
|
||||||
union {
|
union {
|
||||||
sirf_geonav nav;
|
sirf_geonav nav;
|
||||||
uint8_t bytes[];
|
uint8_t bytes[1];
|
||||||
} _buffer;
|
} _buffer;
|
||||||
|
|
||||||
bool _parse_gps(void);
|
bool _parse_gps(void);
|
||||||
|
@ -384,7 +384,7 @@ private:
|
|||||||
ubx_rxm_rawx rxm_rawx;
|
ubx_rxm_rawx rxm_rawx;
|
||||||
#endif
|
#endif
|
||||||
ubx_ack_ack ack;
|
ubx_ack_ack ack;
|
||||||
uint8_t bytes[];
|
uint8_t bytes[1];
|
||||||
} _buffer;
|
} _buffer;
|
||||||
|
|
||||||
enum ubs_protocol_bytes {
|
enum ubs_protocol_bytes {
|
||||||
|
Loading…
Reference in New Issue
Block a user