AP_GPS: use ARRAY_SUBSCRIPT instead of bytes field

That fixed compilation issues and seems more semantically correct. Using array
of length 0 fails compilation because of -Werror=array-bounds in GCC 6.1.
This commit is contained in:
Gustavo Jose de Sousa 2016-06-06 10:49:46 -03:00 committed by Lucas De Marchi
parent 1962acad49
commit 174cefa8a5
10 changed files with 10 additions and 10 deletions

View File

@ -110,7 +110,7 @@ AP_GPS_ERB::read(void)
case 5:
_ck_b += (_ck_a += data); // checksum byte
if (_payload_counter < sizeof(_buffer)) {
_buffer.bytes[_payload_counter] = data;
_buffer[_payload_counter] = data;
}
if (++_payload_counter == _payload_length)
_step++;

View File

@ -85,12 +85,12 @@ private:
// Receive buffer
union PACKED {
DEFINE_BYTE_ARRAY_METHODS
erb_ver ver;
erb_pos pos;
erb_stat stat;
erb_dops dops;
erb_vel vel;
uint8_t bytes[0];
} _buffer;
enum erb_protocol_bytes {

View File

@ -115,7 +115,7 @@ restart:
// Receive message data
//
case 4:
_buffer.bytes[_payload_counter++] = data;
_buffer[_payload_counter++] = data;
_ck_b += (_ck_a += data);
if (_payload_counter == sizeof(_buffer))
_step++;

View File

@ -71,8 +71,8 @@ private:
// Receive buffer
union PACKED {
DEFINE_BYTE_ARRAY_METHODS
diyd_mtk_msg msg;
uint8_t bytes[0];
} _buffer;
// Buffer parse & GPS state update

View File

@ -105,7 +105,7 @@ restart:
// Receive message data
//
case 3:
_buffer.bytes[_payload_counter++] = data;
_buffer[_payload_counter++] = data;
_ck_b += (_ck_a += data);
if (_payload_counter == sizeof(_buffer)) {
_step++;

View File

@ -77,7 +77,7 @@ private:
// Receive buffer
union {
DEFINE_BYTE_ARRAY_METHODS
diyd_mtk_msg msg;
uint8_t bytes[0];
} _buffer;
};

View File

@ -138,7 +138,7 @@ AP_GPS_SIRF::read(void)
case 5:
if (_gather) { // gather data if requested
_accumulate(data);
_buffer.bytes[_payload_counter] = data;
_buffer[_payload_counter] = data;
if (++_payload_counter == _payload_length)
_step++;
} else {

View File

@ -97,8 +97,8 @@ private:
// Message buffer
union {
DEFINE_BYTE_ARRAY_METHODS
sirf_geonav nav;
uint8_t bytes[0];
} _buffer;
bool _parse_gps(void);

View File

@ -431,7 +431,7 @@ AP_GPS_UBLOX::read(void)
case 6:
_ck_b += (_ck_a += data); // checksum byte
if (_payload_counter < sizeof(_buffer)) {
_buffer.bytes[_payload_counter] = data;
_buffer[_payload_counter] = data;
}
if (++_payload_counter == _payload_length)
_step++;

View File

@ -360,6 +360,7 @@ private:
// Receive buffer
union PACKED {
DEFINE_BYTE_ARRAY_METHODS
ubx_nav_posllh posllh;
ubx_nav_status status;
ubx_nav_dop dop;
@ -384,7 +385,6 @@ private:
ubx_rxm_rawx rxm_rawx;
#endif
ubx_ack_ack ack;
uint8_t bytes[0];
} _buffer;
enum ubs_protocol_bytes {