mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: use PACKED attribute instead of pragma pack
This commit is contained in:
parent
62b9a580e8
commit
06b6f4b04e
@ -16,6 +16,7 @@
|
||||
#define __AP_GPS_MTK_H__
|
||||
|
||||
#include "GPS.h"
|
||||
#include <AP_Common.h>
|
||||
#include "AP_GPS_MTK_Common.h"
|
||||
|
||||
class AP_GPS_MTK : public GPS {
|
||||
@ -31,8 +32,7 @@ public:
|
||||
static bool _detect(uint8_t );
|
||||
|
||||
private:
|
||||
#pragma pack(push,1)
|
||||
struct diyd_mtk_msg {
|
||||
struct PACKED diyd_mtk_msg {
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
int32_t altitude;
|
||||
@ -42,7 +42,6 @@ private:
|
||||
uint8_t fix_type;
|
||||
uint32_t utc_time;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
enum diyd_mtk_fix_type {
|
||||
FIX_NONE = 1,
|
||||
FIX_2D = 2,
|
||||
@ -65,7 +64,7 @@ private:
|
||||
uint8_t _payload_counter;
|
||||
|
||||
// Receive buffer
|
||||
union {
|
||||
union PACKED {
|
||||
diyd_mtk_msg msg;
|
||||
uint8_t bytes[];
|
||||
} _buffer;
|
||||
|
@ -14,6 +14,7 @@
|
||||
#define AP_GPS_MTK19_h
|
||||
|
||||
#include "GPS.h"
|
||||
#include <AP_Common.h>
|
||||
#include "AP_GPS_MTK_Common.h"
|
||||
|
||||
#define MTK_GPS_REVISION_V16 16
|
||||
@ -34,8 +35,7 @@ public:
|
||||
static bool _detect(uint8_t );
|
||||
|
||||
private:
|
||||
#pragma pack(push,1)
|
||||
struct diyd_mtk_msg {
|
||||
struct PACKED diyd_mtk_msg {
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
int32_t altitude;
|
||||
@ -47,7 +47,6 @@ private:
|
||||
uint32_t utc_time;
|
||||
uint16_t hdop;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
enum diyd_mtk_fix_type {
|
||||
FIX_NONE = 1,
|
||||
FIX_2D = 2,
|
||||
|
@ -12,6 +12,7 @@
|
||||
#define __AP_GPS_SIRF_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Common.h>
|
||||
#include "GPS.h"
|
||||
|
||||
#define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C"
|
||||
@ -32,8 +33,7 @@ public:
|
||||
static bool _detect(uint8_t data);
|
||||
|
||||
private:
|
||||
#pragma pack(push,1)
|
||||
struct sirf_geonav {
|
||||
struct PACKED sirf_geonav {
|
||||
uint16_t fix_invalid;
|
||||
uint16_t fix_type;
|
||||
uint16_t week;
|
||||
@ -70,7 +70,6 @@ private:
|
||||
uint8_t hdop;
|
||||
uint8_t mode_info;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
enum sirf_protocol_bytes {
|
||||
PREAMBLE1 = 0xa0,
|
||||
PREAMBLE2 = 0xa2,
|
||||
|
@ -13,6 +13,7 @@
|
||||
#define __AP_GPS_UBLOX_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Common.h>
|
||||
#include "GPS.h"
|
||||
|
||||
/*
|
||||
@ -55,25 +56,24 @@ public:
|
||||
|
||||
private:
|
||||
// u-blox UBX protocol essentials
|
||||
#pragma pack(push,1)
|
||||
struct ubx_header {
|
||||
struct PACKED ubx_header {
|
||||
uint8_t preamble1;
|
||||
uint8_t preamble2;
|
||||
uint8_t msg_class;
|
||||
uint8_t msg_id;
|
||||
uint16_t length;
|
||||
};
|
||||
struct ubx_cfg_nav_rate {
|
||||
struct PACKED ubx_cfg_nav_rate {
|
||||
uint16_t measure_rate_ms;
|
||||
uint16_t nav_rate;
|
||||
uint16_t timeref;
|
||||
};
|
||||
struct ubx_cfg_msg_rate {
|
||||
struct PACKED ubx_cfg_msg_rate {
|
||||
uint8_t msg_class;
|
||||
uint8_t msg_id;
|
||||
uint8_t rate;
|
||||
};
|
||||
struct ubx_cfg_nav_settings {
|
||||
struct PACKED ubx_cfg_nav_settings {
|
||||
uint16_t mask;
|
||||
uint8_t dynModel;
|
||||
uint8_t fixMode;
|
||||
@ -92,7 +92,7 @@ private:
|
||||
uint32_t res4;
|
||||
};
|
||||
|
||||
struct ubx_nav_posllh {
|
||||
struct PACKED ubx_nav_posllh {
|
||||
uint32_t time; // GPS msToW
|
||||
int32_t longitude;
|
||||
int32_t latitude;
|
||||
@ -101,7 +101,7 @@ private:
|
||||
uint32_t horizontal_accuracy;
|
||||
uint32_t vertical_accuracy;
|
||||
};
|
||||
struct ubx_nav_status {
|
||||
struct PACKED ubx_nav_status {
|
||||
uint32_t time; // GPS msToW
|
||||
uint8_t fix_type;
|
||||
uint8_t fix_status;
|
||||
@ -110,7 +110,7 @@ private:
|
||||
uint32_t time_to_first_fix;
|
||||
uint32_t uptime; // milliseconds
|
||||
};
|
||||
struct ubx_nav_solution {
|
||||
struct PACKED ubx_nav_solution {
|
||||
uint32_t time;
|
||||
int32_t time_nsec;
|
||||
int16_t week;
|
||||
@ -129,7 +129,7 @@ private:
|
||||
uint8_t satellites;
|
||||
uint32_t res2;
|
||||
};
|
||||
struct ubx_nav_velned {
|
||||
struct PACKED ubx_nav_velned {
|
||||
uint32_t time; // GPS msToW
|
||||
int32_t ned_north;
|
||||
int32_t ned_east;
|
||||
@ -141,7 +141,7 @@ private:
|
||||
uint32_t heading_accuracy;
|
||||
};
|
||||
// Receive buffer
|
||||
union {
|
||||
union PACKED {
|
||||
ubx_nav_posllh posllh;
|
||||
ubx_nav_status status;
|
||||
ubx_nav_solution solution;
|
||||
@ -149,7 +149,6 @@ private:
|
||||
ubx_cfg_nav_settings nav_settings;
|
||||
uint8_t bytes[];
|
||||
} _buffer;
|
||||
#pragma pack(pop)
|
||||
|
||||
enum ubs_protocol_bytes {
|
||||
PREAMBLE1 = 0xb5,
|
||||
|
Loading…
Reference in New Issue
Block a user