19 #define GPS_BACKEND_DEBUGGING 0 21 #if GPS_BACKEND_DEBUGGING 22 # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) 24 # define Debug(fmt, args ...) 43 const uint8_t *b = (
const uint8_t *)&v;
59 const uint8_t *b = (
const uint8_t *)&v;
78 uint8_t year, mon, day, hour, min, sec;
81 year = bcd_date % 100;
82 mon = (bcd_date / 100) % 100;
83 day = bcd_date / 10000;
85 uint32_t
v = bcd_milliseconds;
86 msec = v % 1000; v /= 1000;
87 sec = v % 100; v /= 100;
88 min = v % 100; v /= 100;
89 hour = v % 100; v /= 100;
91 int8_t rmon = mon - 2;
99 ret += year*365 + 10501;
130 if (
port !=
nullptr) {
146 "GPS %d: detected as %s at %d baud",
152 "GPS %d: specified as %s",
185 mavlink_msg_gps_rtk_send(chan,
201 mavlink_msg_gps2_rtk_send(chan,
#define GPS_LEAPSECONDS_MILLIS
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
uint16_t rtk_week_number
GPS Week Number of last baseline.
Interface definition for the various Ground Control System.
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
static uint8_t buffer[SRXL_FRAMELEN_MAX]
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
void Log_Write_Message(const char *message)
virtual void inject_data(const uint8_t *data, uint16_t len)
virtual uint32_t txspace()=0
bool should_df_log() const
#define Debug(fmt, args ...)
int32_t rtk_baseline_y_mm
Current baseline in ECEF y or NED east component in mm.
int32_t swap_int32(int32_t v) const
AP_GPS & gps
access to frontend (for parameters)
virtual const char * name() const =0
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
virtual size_t write(uint8_t)=0
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan)
uint8_t rtk_baseline_coords_type
Coordinate system of baseline. 0 == ECEF, 1 == NED.
int32_t rtk_iar_num_hypotheses
Current number of integer ambiguity hypotheses.
static DataFlash_Class * instance(void)
void broadcast_gps_type() const
uint16_t time_week
GPS week number.
AP_GPS::GPS_State & state
public state for this instance
void send_text(MAV_SEVERITY severity, const char *fmt,...)
bool should_df_log() const
void _detection_message(char *buffer, uint8_t buflen) const
AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
uint32_t rtk_accuracy
Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
static const uint32_t _baudrates[]
int snprintf(char *str, size_t size, const char *format,...)
static constexpr float radians(float deg)
void fill_3d_velocity(void)
int16_t swap_int16(int16_t v) const
AP_HAL::AnalogSource * chan
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
uint32_t rtk_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.
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 ground_speed
ground speed in m/sec
virtual void Write_DataFlash_Log_Startup_messages() const
struct AP_GPS::detect_state detect_state[GPS_MAX_RECEIVERS]
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.