mirror of https://github.com/ArduPilot/ardupilot
AP_Mount 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_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. In file included from ../../libraries/AP_Mount/AP_Mount.cpp:9:0: ../../libraries/AP_Mount/AP_Mount_Alexmos.h:291:23: error: flexible array member in union uint8_t bytes[]; ^ compilation terminated due to -Wfatal-errors.
This commit is contained in:
parent
39bd196481
commit
421b9ef54a
|
@ -288,7 +288,7 @@ private:
|
|||
alexmos_angles angles;
|
||||
alexmos_params params;
|
||||
alexmos_angles_speed angle_speed;
|
||||
uint8_t bytes[];
|
||||
uint8_t bytes[1];
|
||||
} _buffer,_current_parameters;
|
||||
|
||||
AP_HAL::UARTDriver *_port;
|
||||
|
|
|
@ -145,7 +145,7 @@ private:
|
|||
union PACKED SToRM32_reply {
|
||||
SToRM32_reply_data_struct data;
|
||||
SToRM32_reply_ack_struct ack;
|
||||
uint8_t bytes[];
|
||||
uint8_t bytes[1];
|
||||
} _buffer;
|
||||
|
||||
// keep the last _current_angle values
|
||||
|
|
Loading…
Reference in New Issue