mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_GPS/AP_GPS_SIRF.h
This commit is contained in:
parent
f23d3daca9
commit
31d2076794
|
@ -13,53 +13,53 @@
|
||||||
|
|
||||||
#include "GPS.h"
|
#include "GPS.h"
|
||||||
|
|
||||||
#define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C"
|
#define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C"
|
||||||
|
|
||||||
class AP_GPS_SIRF : public GPS {
|
class AP_GPS_SIRF : public GPS {
|
||||||
public:
|
public:
|
||||||
AP_GPS_SIRF(Stream *s);
|
AP_GPS_SIRF(Stream *s);
|
||||||
|
|
||||||
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
||||||
virtual bool read();
|
virtual bool read();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// XXX this is being ignored by the compiler #pragma pack(1)
|
// XXX this is being ignored by the compiler #pragma pack(1)
|
||||||
struct sirf_geonav {
|
struct sirf_geonav {
|
||||||
uint16_t fix_invalid;
|
uint16_t fix_invalid;
|
||||||
uint16_t fix_type;
|
uint16_t fix_type;
|
||||||
uint16_t week;
|
uint16_t week;
|
||||||
uint32_t time;
|
uint32_t time;
|
||||||
uint16_t year;
|
uint16_t year;
|
||||||
uint8_t month;
|
uint8_t month;
|
||||||
uint8_t day;
|
uint8_t day;
|
||||||
uint8_t hour;
|
uint8_t hour;
|
||||||
uint8_t minute;
|
uint8_t minute;
|
||||||
uint16_t second;
|
uint16_t second;
|
||||||
uint32_t satellites_used;
|
uint32_t satellites_used;
|
||||||
int32_t latitude;
|
int32_t latitude;
|
||||||
int32_t longitude;
|
int32_t longitude;
|
||||||
int32_t altitude_ellipsoid;
|
int32_t altitude_ellipsoid;
|
||||||
int32_t altitude_msl;
|
int32_t altitude_msl;
|
||||||
int8_t map_datum;
|
int8_t map_datum;
|
||||||
int16_t ground_speed;
|
int16_t ground_speed;
|
||||||
int16_t ground_course;
|
int16_t ground_course;
|
||||||
int16_t res1;
|
int16_t res1;
|
||||||
int16_t climb_rate;
|
int16_t climb_rate;
|
||||||
uint16_t heading_rate;
|
uint16_t heading_rate;
|
||||||
uint32_t horizontal_position_error;
|
uint32_t horizontal_position_error;
|
||||||
uint32_t vertical_position_error;
|
uint32_t vertical_position_error;
|
||||||
uint32_t time_error;
|
uint32_t time_error;
|
||||||
int16_t horizontal_velocity_error;
|
int16_t horizontal_velocity_error;
|
||||||
int32_t clock_bias;
|
int32_t clock_bias;
|
||||||
uint32_t clock_bias_error;
|
uint32_t clock_bias_error;
|
||||||
int32_t clock_drift;
|
int32_t clock_drift;
|
||||||
uint32_t clock_drift_error;
|
uint32_t clock_drift_error;
|
||||||
uint32_t distance;
|
uint32_t distance;
|
||||||
uint16_t distance_error;
|
uint16_t distance_error;
|
||||||
uint16_t heading_error;
|
uint16_t heading_error;
|
||||||
uint8_t satellites;
|
uint8_t satellites;
|
||||||
uint8_t hdop;
|
uint8_t hdop;
|
||||||
uint8_t mode_info;
|
uint8_t mode_info;
|
||||||
};
|
};
|
||||||
// #pragma pack(pop)
|
// #pragma pack(pop)
|
||||||
enum sirf_protocol_bytes {
|
enum sirf_protocol_bytes {
|
||||||
|
@ -76,21 +76,21 @@ private:
|
||||||
|
|
||||||
|
|
||||||
// State machine state
|
// State machine state
|
||||||
uint8_t _step;
|
uint8_t _step;
|
||||||
uint16_t _checksum;
|
uint16_t _checksum;
|
||||||
bool _gather;
|
bool _gather;
|
||||||
uint16_t _payload_length;
|
uint16_t _payload_length;
|
||||||
uint16_t _payload_counter;
|
uint16_t _payload_counter;
|
||||||
uint8_t _msg_id;
|
uint8_t _msg_id;
|
||||||
|
|
||||||
// Message buffer
|
// Message buffer
|
||||||
union {
|
union {
|
||||||
sirf_geonav nav;
|
sirf_geonav nav;
|
||||||
uint8_t bytes[];
|
uint8_t bytes[];
|
||||||
} _buffer;
|
} _buffer;
|
||||||
|
|
||||||
bool _parse_gps(void);
|
bool _parse_gps(void);
|
||||||
void _accumulate(uint8_t val);
|
void _accumulate(uint8_t val);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_GPS_SIRF_h
|
#endif // AP_GPS_SIRF_h
|
||||||
|
|
Loading…
Reference in New Issue