From ed918dc6bc128f94d72bf133b4eb185263ebf831 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 9 May 2013 20:04:45 +1000 Subject: [PATCH] SITL: use PACKED attribute instead of pragma pack --- libraries/AP_HAL_AVR_SITL/sitl_gps.cpp | 24 ++++++++---------------- 1 file changed, 8 insertions(+), 16 deletions(-) diff --git a/libraries/AP_HAL_AVR_SITL/sitl_gps.cpp b/libraries/AP_HAL_AVR_SITL/sitl_gps.cpp index e2e3604c75..b8ba5d6d4d 100644 --- a/libraries/AP_HAL_AVR_SITL/sitl_gps.cpp +++ b/libraries/AP_HAL_AVR_SITL/sitl_gps.cpp @@ -145,8 +145,7 @@ static uint32_t millis_time_of_week(void) */ void SITL_State::_update_gps_ubx(const struct gps_data *d) { - #pragma pack(push,1) - struct ubx_nav_posllh { + struct PACKED ubx_nav_posllh { uint32_t time; // GPS msToW int32_t longitude; int32_t latitude; @@ -155,7 +154,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d) uint32_t horizontal_accuracy; uint32_t vertical_accuracy; } pos; - struct ubx_nav_status { + struct PACKED ubx_nav_status { uint32_t time; // GPS msToW uint8_t fix_type; uint8_t fix_status; @@ -164,7 +163,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d) uint32_t time_to_first_fix; uint32_t uptime; // milliseconds } status; - struct ubx_nav_velned { + struct PACKED ubx_nav_velned { uint32_t time; // GPS msToW int32_t ned_north; int32_t ned_east; @@ -175,7 +174,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d) uint32_t speed_accuracy; uint32_t heading_accuracy; } velned; - struct ubx_nav_solution { + struct PACKED ubx_nav_solution { uint32_t time; int32_t time_nsec; int16_t week; @@ -194,8 +193,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d) uint8_t satellites; uint32_t res2; } sol; - #pragma pack(pop) - const uint8_t MSG_POSLLH = 0x2; + const uint8_t MSG_POSLLH = 0x2; const uint8_t MSG_STATUS = 0x3; const uint8_t MSG_VELNED = 0x12; const uint8_t MSG_SOL = 0x6; @@ -266,8 +264,7 @@ static void mtk_checksum(const uint8_t *data, uint8_t n, uint8_t *ck_a, uint8_t */ void SITL_State::_update_gps_mtk(const struct gps_data *d) { - #pragma pack(push,1) - struct mtk_msg { + struct PACKED mtk_msg { uint8_t preamble1; uint8_t preamble2; uint8_t msg_class; @@ -283,7 +280,6 @@ void SITL_State::_update_gps_mtk(const struct gps_data *d) uint8_t ck_a; uint8_t ck_b; } p; - #pragma pack(pop) p.preamble1 = 0xb5; p.preamble2 = 0x62; @@ -322,8 +318,7 @@ void SITL_State::_update_gps_mtk(const struct gps_data *d) */ void SITL_State::_update_gps_mtk16(const struct gps_data *d) { - #pragma pack(push,1) - struct mtk_msg { + struct PACKED mtk_msg { uint8_t preamble1; uint8_t preamble2; uint8_t size; @@ -340,7 +335,6 @@ void SITL_State::_update_gps_mtk16(const struct gps_data *d) uint8_t ck_a; uint8_t ck_b; } p; - #pragma pack(pop) p.preamble1 = 0xd0; p.preamble2 = 0xdd; @@ -380,8 +374,7 @@ void SITL_State::_update_gps_mtk16(const struct gps_data *d) */ void SITL_State::_update_gps_mtk19(const struct gps_data *d) { - #pragma pack(push,1) - struct mtk_msg { + struct PACKED mtk_msg { uint8_t preamble1; uint8_t preamble2; uint8_t size; @@ -398,7 +391,6 @@ void SITL_State::_update_gps_mtk19(const struct gps_data *d) uint8_t ck_a; uint8_t ck_b; } p; - #pragma pack(pop) p.preamble1 = 0xd1; p.preamble2 = 0xdd;