28 #define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C\r\n" 38 const char *
name()
const override {
return "SIRF"; }
int32_t altitude_ellipsoid
DEFINE_BYTE_ARRAY_METHODS sirf_geonav nav
int16_t horizontal_velocity_error
uint16_t _payload_counter
#define DEFINE_BYTE_ARRAY_METHODS
AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
uint32_t clock_bias_error
uint32_t vertical_position_error
AP_GPS::GPS_State & state
public state for this instance
Common definitions and utility routines for the ArduPilot libraries.
uint32_t clock_drift_error
union AP_GPS_SIRF::@35 _buffer
uint32_t horizontal_position_error
static bool _detect(struct SIRF_detect_state &state, uint8_t data)
const char * name() const override
void _accumulate(uint8_t val)
static const uint8_t _initialisation_blob[]