23 #define ERB_DEBUGGING 0 25 #define STAT_FIX_VALID 0x01 30 # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) 32 # define Debug(fmt, args ...) 58 for (int16_t i = 0; i < numc; i++) {
74 Debug(
"reset %u", __LINE__);
116 Debug(
"bad cka %x should be %x", data,
_ck_a);
124 Debug(
"bad ckb %x should be %x", data,
_ck_b);
142 Debug(
"Version of ERB protocol %u.%u.%u",
148 Debug(
"Message POS");
161 Debug(
"Message STAT fix_status=%u fix_type=%u",
187 Debug(
"Message DOPS");
192 Debug(
"Message VEL");
206 Debug(
"Message RTK");
244 switch (state.
step) {
277 if (state.
ck_a != data) {
284 if (state.
ck_b == data) {
uint32_t speed_2d
Ground speed (2-D) [cm/s].
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
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.
uint16_t rtk_week_number
GPS Week Number of last baseline.
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
GPS_Status status
driver fix status
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
int32_t rtk_baseline_z_mm
Current baseline in ECEF z or NED down component in mm.
Vector3f velocity
3D velocity in m/s, in NED format
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
int32_t vel_down
Down velocity component [cm/s].
uint8_t fix_type
see erb_fix_type enum
#define Debug(fmt, args ...)
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
int32_t lat
param 3 - Latitude * 10**7
int32_t rtk_baseline_y_mm
Current baseline in ECEF y or NED east component in mm.
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].
float wrap_360(const T angle, float unit_mod)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
uint16_t _payload_counter
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
uint32_t horizontal_accuracy
Horizontal accuracy estimate [mm].
Receiving valid messages and 3D RTK Float.
AP_GPS::GPS_Status next_fix
uint8_t rtk_baseline_coords_type
Coordinate system of baseline. 0 == ECEF, 1 == NED.
uint16_t time_week
GPS week number.
uint32_t rtk_age_ms
GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates over...
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 vdop
vertical dilution of precision in cm
uint32_t rtk_accuracy
Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
virtual uint32_t available()=0
Location location
last fix location
uint16_t hDOP
Horizontal DOP.
int32_t lng
param 4 - Longitude * 10**7
AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Receiving valid GPS messages but no lock.
int32_t baseline_E_mm
distance between base and rover along the east axis in millimeters
uint32_t rtk_time_week_ms
GPS Time of Week of last baseline in milliseconds.
uint32_t base_time_week_ms
GPS Time of Week of last baseline in milliseconds.
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
float speed_accuracy
3D velocity RMS accuracy estimate in m/s
AP_HAL::UARTDriver * port
UART we are attached to.
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
float horizontal_accuracy
horizontal RMS accuracy estimate in m
float ground_speed
ground speed in m/sec
Receiving valid messages and 3D lock.
float vertical_accuracy
vertical RMS accuracy estimate in m
uint16_t hdop
horizontal dilution of precision in cm
uint16_t age_cs
Age of the corrections in centiseconds (0 when no corrections, 0xFFFF indicates overflow) ...
uint8_t num_sats
Number of visible satellites.
int32_t vel_north
North velocity component [cm/s].
int32_t vel_east
East velocity component [cm/s].
bool have_speed_accuracy
does GPS give speed accuracy? Set to true only once available.
float ground_course
ground course in degrees
int32_t rtk_baseline_x_mm
Current baseline in ECEF x or NED north component in mm.