Browse Source

AP_Mount: 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.
mission-4.1.18
Gustavo Jose de Sousa 9 years ago committed by Lucas De Marchi
parent
commit
f9cb760691
  1. 2
      libraries/AP_Mount/AP_Mount_Alexmos.cpp
  2. 2
      libraries/AP_Mount/AP_Mount_Alexmos.h
  3. 7
      libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp
  4. 2
      libraries/AP_Mount/AP_Mount_SToRM32_serial.h

2
libraries/AP_Mount/AP_Mount_Alexmos.cpp

@ -267,7 +267,7 @@ void AP_Mount_Alexmos::read_incoming() @@ -267,7 +267,7 @@ void AP_Mount_Alexmos::read_incoming()
case 4: // parsing body
_checksum += data;
if (_payload_counter < sizeof(_buffer)) {
_buffer.bytes[_payload_counter] = data;
_buffer[_payload_counter] = data;
}
if (++_payload_counter == _payload_length)
_step++;

2
libraries/AP_Mount/AP_Mount_Alexmos.h

@ -284,11 +284,11 @@ private: @@ -284,11 +284,11 @@ private:
};
union PACKED alexmos_parameters {
DEFINE_BYTE_ARRAY_METHODS
alexmos_version version;
alexmos_angles angles;
alexmos_params params;
alexmos_angles_speed angle_speed;
uint8_t bytes[0];
} _buffer,_current_parameters;
AP_HAL::UARTDriver *_port;

7
libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp

@ -236,7 +236,7 @@ void AP_Mount_SToRM32_serial::read_incoming() { @@ -236,7 +236,7 @@ void AP_Mount_SToRM32_serial::read_incoming() {
continue;
}
_buffer.bytes[_reply_counter++] = data;
_buffer[_reply_counter++] = data;
if (_reply_counter == _reply_length) {
parse_reply();
@ -266,7 +266,7 @@ void AP_Mount_SToRM32_serial::parse_reply() { @@ -266,7 +266,7 @@ void AP_Mount_SToRM32_serial::parse_reply() {
switch (_reply_type) {
case ReplyType_DATA:
crc = crc_calculate(_buffer.bytes, sizeof(_buffer.data)-3);
crc = crc_calculate(&_buffer[0], sizeof(_buffer.data) - 3);
crc_ok = crc == _buffer.data.crc;
if (!crc_ok) {
break;
@ -277,7 +277,8 @@ void AP_Mount_SToRM32_serial::parse_reply() { @@ -277,7 +277,8 @@ void AP_Mount_SToRM32_serial::parse_reply() {
_current_angle.z = _buffer.data.imu1_yaw;
break;
case ReplyType_ACK:
crc = crc_calculate(&_buffer.bytes[1], sizeof(SToRM32_reply_ack_struct)-3);
crc = crc_calculate(&_buffer[1],
sizeof(SToRM32_reply_ack_struct) - 3);
crc_ok = crc == _buffer.ack.crc;
break;
default:

2
libraries/AP_Mount/AP_Mount_SToRM32_serial.h

@ -143,9 +143,9 @@ private: @@ -143,9 +143,9 @@ private:
union PACKED SToRM32_reply {
DEFINE_BYTE_ARRAY_METHODS
SToRM32_reply_data_struct data;
SToRM32_reply_ack_struct ack;
uint8_t bytes[0];
} _buffer;
// keep the last _current_angle values

Loading…
Cancel
Save