From 174cefa8a57400a6e96fd4111807e72ed6cdaa2e Mon Sep 17 00:00:00 2001 From: Gustavo Jose de Sousa Date: Mon, 6 Jun 2016 10:49:46 -0300 Subject: [PATCH] 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. --- libraries/AP_GPS/AP_GPS_ERB.cpp | 2 +- libraries/AP_GPS/AP_GPS_ERB.h | 2 +- libraries/AP_GPS/AP_GPS_MTK.cpp | 2 +- libraries/AP_GPS/AP_GPS_MTK.h | 2 +- libraries/AP_GPS/AP_GPS_MTK19.cpp | 2 +- libraries/AP_GPS/AP_GPS_MTK19.h | 2 +- libraries/AP_GPS/AP_GPS_SIRF.cpp | 2 +- libraries/AP_GPS/AP_GPS_SIRF.h | 2 +- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 2 +- libraries/AP_GPS/AP_GPS_UBLOX.h | 2 +- 10 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_ERB.cpp b/libraries/AP_GPS/AP_GPS_ERB.cpp index e1e55c5db2..80ba47de97 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.cpp +++ b/libraries/AP_GPS/AP_GPS_ERB.cpp @@ -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++; diff --git a/libraries/AP_GPS/AP_GPS_ERB.h b/libraries/AP_GPS/AP_GPS_ERB.h index c7d8868c62..537c6699df 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.h +++ b/libraries/AP_GPS/AP_GPS_ERB.h @@ -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 { diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 0822777708..385d840388 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -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++; diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h index 71cedd4303..0b203b79bc 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.h +++ b/libraries/AP_GPS/AP_GPS_MTK.h @@ -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 diff --git a/libraries/AP_GPS/AP_GPS_MTK19.cpp b/libraries/AP_GPS/AP_GPS_MTK19.cpp index 645e068f8f..4780ba9460 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK19.cpp @@ -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++; diff --git a/libraries/AP_GPS/AP_GPS_MTK19.h b/libraries/AP_GPS/AP_GPS_MTK19.h index b6e5c49653..99063e92a9 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.h +++ b/libraries/AP_GPS/AP_GPS_MTK19.h @@ -77,7 +77,7 @@ private: // Receive buffer union { + DEFINE_BYTE_ARRAY_METHODS diyd_mtk_msg msg; - uint8_t bytes[0]; } _buffer; }; diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index 73cc480c23..cb9902a245 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -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 { diff --git a/libraries/AP_GPS/AP_GPS_SIRF.h b/libraries/AP_GPS/AP_GPS_SIRF.h index dfb7a43537..e8df067af7 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.h +++ b/libraries/AP_GPS/AP_GPS_SIRF.h @@ -97,8 +97,8 @@ private: // Message buffer union { + DEFINE_BYTE_ARRAY_METHODS sirf_geonav nav; - uint8_t bytes[0]; } _buffer; bool _parse_gps(void); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index d183fe5270..1aea7c1bec 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -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++; diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index 5dce69d3d7..aa16e90ebd 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -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 {