mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_GPS/AP_GPS_UBLOX.h
This commit is contained in:
parent
ceed417538
commit
c1454461ee
|
@ -14,11 +14,11 @@
|
|||
#include "GPS.h"
|
||||
|
||||
/*
|
||||
try to put a UBlox into binary mode. This is in two parts. First we
|
||||
send a PUBX asking the UBlox to receive NMEA and UBX, and send UBX,
|
||||
with a baudrate of 38400. Then we send a UBX message setting rate 1
|
||||
for the NAV_SOL message. The setup of NAV_SOL is to cope with
|
||||
configurations where all UBX binary message types are disabled.
|
||||
* try to put a UBlox into binary mode. This is in two parts. First we
|
||||
* send a PUBX asking the UBlox to receive NMEA and UBX, and send UBX,
|
||||
* with a baudrate of 38400. Then we send a UBX message setting rate 1
|
||||
* for the NAV_SOL message. The setup of NAV_SOL is to cope with
|
||||
* configurations where all UBX binary message types are disabled.
|
||||
*/
|
||||
#define UBLOX_SET_BINARY "$PUBX,41,1,0003,0001,38400,0*26\n\265\142\006\001\003\000\001\006\001\022\117"
|
||||
|
||||
|
@ -27,98 +27,98 @@ class AP_GPS_UBLOX : public GPS
|
|||
public:
|
||||
// Methods
|
||||
AP_GPS_UBLOX(Stream *s);
|
||||
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
||||
virtual bool read();
|
||||
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
||||
virtual bool read();
|
||||
|
||||
static const prog_char _ublox_set_binary[];
|
||||
static const uint8_t _ublox_set_binary_size;
|
||||
static const prog_char _ublox_set_binary[];
|
||||
static const uint8_t _ublox_set_binary_size;
|
||||
|
||||
private:
|
||||
// u-blox UBX protocol essentials
|
||||
// XXX this is being ignored by the compiler #pragma pack(1)
|
||||
struct ubx_header {
|
||||
uint8_t preamble1;
|
||||
uint8_t preamble2;
|
||||
uint8_t msg_class;
|
||||
uint8_t msg_id;
|
||||
uint16_t length;
|
||||
};
|
||||
struct ubx_cfg_nav_rate {
|
||||
uint16_t measure_rate_ms;
|
||||
uint16_t nav_rate;
|
||||
uint16_t timeref;
|
||||
};
|
||||
struct ubx_cfg_msg_rate {
|
||||
uint8_t msg_class;
|
||||
uint8_t msg_id;
|
||||
uint8_t rate;
|
||||
};
|
||||
struct ubx_cfg_nav_settings {
|
||||
uint16_t mask;
|
||||
uint8_t dynModel;
|
||||
uint8_t fixMode;
|
||||
int32_t fixedAlt;
|
||||
uint32_t fixedAltVar;
|
||||
int8_t minElev;
|
||||
uint8_t drLimit;
|
||||
uint16_t pDop;
|
||||
uint16_t tDop;
|
||||
uint16_t pAcc;
|
||||
uint16_t tAcc;
|
||||
uint8_t staticHoldThresh;
|
||||
uint8_t res1;
|
||||
uint32_t res2;
|
||||
uint32_t res3;
|
||||
uint32_t res4;
|
||||
};
|
||||
struct ubx_header {
|
||||
uint8_t preamble1;
|
||||
uint8_t preamble2;
|
||||
uint8_t msg_class;
|
||||
uint8_t msg_id;
|
||||
uint16_t length;
|
||||
};
|
||||
struct ubx_cfg_nav_rate {
|
||||
uint16_t measure_rate_ms;
|
||||
uint16_t nav_rate;
|
||||
uint16_t timeref;
|
||||
};
|
||||
struct ubx_cfg_msg_rate {
|
||||
uint8_t msg_class;
|
||||
uint8_t msg_id;
|
||||
uint8_t rate;
|
||||
};
|
||||
struct ubx_cfg_nav_settings {
|
||||
uint16_t mask;
|
||||
uint8_t dynModel;
|
||||
uint8_t fixMode;
|
||||
int32_t fixedAlt;
|
||||
uint32_t fixedAltVar;
|
||||
int8_t minElev;
|
||||
uint8_t drLimit;
|
||||
uint16_t pDop;
|
||||
uint16_t tDop;
|
||||
uint16_t pAcc;
|
||||
uint16_t tAcc;
|
||||
uint8_t staticHoldThresh;
|
||||
uint8_t res1;
|
||||
uint32_t res2;
|
||||
uint32_t res3;
|
||||
uint32_t res4;
|
||||
};
|
||||
|
||||
struct ubx_nav_posllh {
|
||||
uint32_t time; // GPS msToW
|
||||
int32_t longitude;
|
||||
int32_t latitude;
|
||||
int32_t altitude_ellipsoid;
|
||||
int32_t altitude_msl;
|
||||
uint32_t horizontal_accuracy;
|
||||
uint32_t vertical_accuracy;
|
||||
uint32_t time; // GPS msToW
|
||||
int32_t longitude;
|
||||
int32_t latitude;
|
||||
int32_t altitude_ellipsoid;
|
||||
int32_t altitude_msl;
|
||||
uint32_t horizontal_accuracy;
|
||||
uint32_t vertical_accuracy;
|
||||
};
|
||||
struct ubx_nav_status {
|
||||
uint32_t time; // GPS msToW
|
||||
uint8_t fix_type;
|
||||
uint8_t fix_status;
|
||||
uint8_t differential_status;
|
||||
uint8_t res;
|
||||
uint32_t time_to_first_fix;
|
||||
uint32_t uptime; // milliseconds
|
||||
uint32_t time; // GPS msToW
|
||||
uint8_t fix_type;
|
||||
uint8_t fix_status;
|
||||
uint8_t differential_status;
|
||||
uint8_t res;
|
||||
uint32_t time_to_first_fix;
|
||||
uint32_t uptime; // milliseconds
|
||||
};
|
||||
struct ubx_nav_solution {
|
||||
uint32_t time;
|
||||
int32_t time_nsec;
|
||||
int16_t week;
|
||||
uint8_t fix_type;
|
||||
uint8_t fix_status;
|
||||
int32_t ecef_x;
|
||||
int32_t ecef_y;
|
||||
int32_t ecef_z;
|
||||
uint32_t position_accuracy_3d;
|
||||
int32_t ecef_x_velocity;
|
||||
int32_t ecef_y_velocity;
|
||||
int32_t ecef_z_velocity;
|
||||
uint32_t speed_accuracy;
|
||||
uint16_t position_DOP;
|
||||
uint8_t res;
|
||||
uint8_t satellites;
|
||||
uint32_t res2;
|
||||
uint32_t time;
|
||||
int32_t time_nsec;
|
||||
int16_t week;
|
||||
uint8_t fix_type;
|
||||
uint8_t fix_status;
|
||||
int32_t ecef_x;
|
||||
int32_t ecef_y;
|
||||
int32_t ecef_z;
|
||||
uint32_t position_accuracy_3d;
|
||||
int32_t ecef_x_velocity;
|
||||
int32_t ecef_y_velocity;
|
||||
int32_t ecef_z_velocity;
|
||||
uint32_t speed_accuracy;
|
||||
uint16_t position_DOP;
|
||||
uint8_t res;
|
||||
uint8_t satellites;
|
||||
uint32_t res2;
|
||||
};
|
||||
struct ubx_nav_velned {
|
||||
uint32_t time; // GPS msToW
|
||||
int32_t ned_north;
|
||||
int32_t ned_east;
|
||||
int32_t ned_down;
|
||||
uint32_t speed_3d;
|
||||
uint32_t speed_2d;
|
||||
int32_t heading_2d;
|
||||
uint32_t speed_accuracy;
|
||||
uint32_t heading_accuracy;
|
||||
uint32_t time; // GPS msToW
|
||||
int32_t ned_north;
|
||||
int32_t ned_east;
|
||||
int32_t ned_down;
|
||||
uint32_t speed_3d;
|
||||
uint32_t speed_2d;
|
||||
int32_t heading_2d;
|
||||
uint32_t speed_accuracy;
|
||||
uint32_t heading_accuracy;
|
||||
};
|
||||
// // #pragma pack(pop)
|
||||
enum ubs_protocol_bytes {
|
||||
|
@ -127,8 +127,8 @@ private:
|
|||
CLASS_NAV = 0x01,
|
||||
CLASS_ACK = 0x05,
|
||||
CLASS_CFG = 0x06,
|
||||
MSG_ACK_NACK = 0x00,
|
||||
MSG_ACK_ACK = 0x01,
|
||||
MSG_ACK_NACK = 0x00,
|
||||
MSG_ACK_ACK = 0x01,
|
||||
MSG_POSLLH = 0x2,
|
||||
MSG_STATUS = 0x3,
|
||||
MSG_SOL = 0x6,
|
||||
|
@ -136,7 +136,7 @@ private:
|
|||
MSG_CFG_PRT = 0x00,
|
||||
MSG_CFG_RATE = 0x08,
|
||||
MSG_CFG_SET_RATE = 0x01,
|
||||
MSG_CFG_NAV_SETTINGS = 0x24
|
||||
MSG_CFG_NAV_SETTINGS = 0x24
|
||||
};
|
||||
enum ubs_nav_fix_type {
|
||||
FIX_NONE = 0,
|
||||
|
@ -151,45 +151,45 @@ private:
|
|||
};
|
||||
|
||||
// Packet checksum accumulators
|
||||
uint8_t _ck_a;
|
||||
uint8_t _ck_b;
|
||||
uint8_t _ck_a;
|
||||
uint8_t _ck_b;
|
||||
|
||||
// State machine state
|
||||
uint8_t _step;
|
||||
uint8_t _msg_id;
|
||||
uint16_t _payload_length;
|
||||
uint16_t _payload_counter;
|
||||
uint8_t _step;
|
||||
uint8_t _msg_id;
|
||||
uint16_t _payload_length;
|
||||
uint16_t _payload_counter;
|
||||
|
||||
uint8_t _class;
|
||||
uint8_t _class;
|
||||
|
||||
// do we have new position information?
|
||||
bool _new_position;
|
||||
// do we have new position information?
|
||||
bool _new_position;
|
||||
|
||||
// do we have new speed information?
|
||||
bool _new_speed;
|
||||
// do we have new speed information?
|
||||
bool _new_speed;
|
||||
|
||||
uint8_t _disable_counter;
|
||||
uint8_t _disable_counter;
|
||||
|
||||
// Receive buffer
|
||||
union {
|
||||
ubx_nav_posllh posllh;
|
||||
ubx_nav_status status;
|
||||
ubx_nav_solution solution;
|
||||
ubx_nav_velned velned;
|
||||
ubx_nav_posllh posllh;
|
||||
ubx_nav_status status;
|
||||
ubx_nav_solution solution;
|
||||
ubx_nav_velned velned;
|
||||
ubx_cfg_nav_settings nav_settings;
|
||||
uint8_t bytes[];
|
||||
uint8_t bytes[];
|
||||
} _buffer;
|
||||
|
||||
// Buffer parse & GPS state update
|
||||
bool _parse_gps();
|
||||
bool _parse_gps();
|
||||
|
||||
// used to update fix between status and position packets
|
||||
bool next_fix;
|
||||
// used to update fix between status and position packets
|
||||
bool next_fix;
|
||||
|
||||
void _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
|
||||
void _configure_gps(void);
|
||||
void _update_checksum(uint8_t *data, uint8_t len, uint8_t &ck_a, uint8_t &ck_b);
|
||||
void _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size);
|
||||
void _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
|
||||
void _configure_gps(void);
|
||||
void _update_checksum(uint8_t *data, uint8_t len, uint8_t &ck_a, uint8_t &ck_b);
|
||||
void _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size);
|
||||
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue