41 const char *
name()
const override {
return "ERB"; }
uint32_t speed_2d
Ground speed (2-D) [cm/s].
uint32_t time
GPS time of week of the navigation epoch [ms].
uint32_t time
GPS time of week of the navigation epoch [ms].
uint8_t base_num_sats
Current number of satellites used for RTK calculation.
bool supports_mavlink_gps_rtk_message()
#define DEFINE_BYTE_ARRAY_METHODS
int32_t heading_2d
Heading of motion 2-D [1e5 deg].
uint32_t vertical_accuracy
Vertical accuracy estimate [mm].
uint32_t speed_accuracy
Speed accuracy Estimate [cm/s].
uint32_t time
GPS time of week of the navigation epoch [ms].
int32_t baseline_N_mm
distance between base and rover along the north axis in millimeters
uint32_t time
GPS time of week of the navigation epoch [ms].
int32_t vel_down
Down velocity component [cm/s].
uint8_t fix_type
see erb_fix_type enum
uint16_t base_week_number
GPS Week Number of last baseline.
static bool _detect(struct ERB_detect_state &state, uint8_t data)
int32_t baseline_D_mm
distance between base and rover along the down axis in millimeters
Receiving valid messages and 3D RTK Fixed.
uint16_t ar_ratio
AR ratio multiplied by 10.
uint16_t vDOP
Vertical DOP.
double altitude_msl
Height above mean sea level [m].
double altitude_ellipsoid
Height above ellipsoid [m].
GPS_Status
GPS status codes.
uint16_t _payload_counter
uint32_t horizontal_accuracy
Horizontal accuracy estimate [mm].
AP_GPS::GPS_Status next_fix
union AP_GPS_ERB::PACKED _buffer
AP_GPS::GPS_State & state
public state for this instance
DEFINE_BYTE_ARRAY_METHODS erb_ver ver
uint32_t time
GPS time of week of the navigation epoch [ms].
uint16_t pDOP
Position DOP.
uint16_t hDOP
Horizontal DOP.
AP_GPS::GPS_Status highest_supported_status(void)
AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
uint16_t gDOP
Geometric DOP.
int32_t baseline_E_mm
distance between base and rover along the east axis in millimeters
uint32_t base_time_week_ms
GPS Time of Week of last baseline in milliseconds.
uint16_t age_cs
Age of the corrections in centiseconds (0 when no corrections, 0xFFFF indicates overflow) ...
int32_t vel_north
North velocity component [cm/s].
int32_t vel_east
East velocity component [cm/s].
const char * name() const override