Paparazzi UAS  v4.0.4_stable-3-gf39211a
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
gps_ubx.h File Reference

UBX protocol specific code. More...

#include "mcu_periph/uart.h"
#include "ubx_protocol.h"
+ Include dependency graph for gps_ubx.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Data Structures

struct  GpsUbx
 

Macros

#define GPS_NB_CHANNELS   16
 Includes macros generated from ubx.xml. More...
 
#define GPS_UBX_MAX_PAYLOAD   255
 
#define __GpsLink(dev, _x)   dev##_x
 
#define _GpsLink(dev, _x)   __GpsLink(dev, _x)
 
#define GpsLink(_x)   _GpsLink(GPS_LINK, _x)
 
#define GpsBuffer()   GpsLink(ChAvailable())
 
#define gps_ubx_ucenter_event()   {}
 
#define GpsEvent(_sol_available_callback)
 
#define ReadGpsBuffer()
 
#define CFG_RST_Reset_Hardware   0x00
 
#define CFG_RST_Reset_Controlled   0x01
 
#define CFG_RST_Reset_Controlled_GPS_only   0x02
 
#define CFG_RST_Reset_Controlled_GPS_stop   0x08
 
#define CFG_RST_Reset_Controlled_GPS_start   0x09
 
#define gps_ubx_Reset(_val)
 

Functions

void gps_ubx_read_message (void)
 
void gps_ubx_parse (uint8_t c)
 
void ubxsend_cfg_rst (uint16_t, uint8_t)
 

Variables

struct GpsUbx gps_ubx
 

Detailed Description

UBX protocol specific code.

Definition in file gps_ubx.h.

Macro Definition Documentation

#define __GpsLink (   dev,
  _x 
)    dev##_x

Definition at line 67 of file gps_ubx.h.

#define _GpsLink (   dev,
  _x 
)    __GpsLink(dev, _x)

Definition at line 68 of file gps_ubx.h.

#define CFG_RST_Reset_Controlled   0x01

Definition at line 119 of file gps_ubx.h.

#define CFG_RST_Reset_Controlled_GPS_only   0x02

Definition at line 120 of file gps_ubx.h.

#define CFG_RST_Reset_Controlled_GPS_start   0x09

Definition at line 122 of file gps_ubx.h.

#define CFG_RST_Reset_Controlled_GPS_stop   0x08

Definition at line 121 of file gps_ubx.h.

#define CFG_RST_Reset_Hardware   0x00

Definition at line 118 of file gps_ubx.h.

#define GPS_NB_CHANNELS   16

Includes macros generated from ubx.xml.

Definition at line 39 of file gps_ubx.h.

#define GPS_UBX_MAX_PAYLOAD   255

Definition at line 41 of file gps_ubx.h.

Referenced by gps_ubx_parse().

#define gps_ubx_Reset (   _val)
Value:
{ \
gps_ubx.reset = _val; \
}
#define CFG_RST_Reset_Controlled
Definition: gps_ubx.h:119
#define CFG_RST_BBR_Coldstart
Definition: gps.h:122
void ubxsend_cfg_rst(uint16_t, uint8_t)
Definition: gps_ubx.c:277
struct GpsUbx gps_ubx
Definition: gps_ubx.c:81
#define CFG_RST_BBR_Warmstart
Definition: gps.h:121

Definition at line 126 of file gps_ubx.h.

#define gps_ubx_ucenter_event (   void)    {}

Definition at line 74 of file gps_ubx.h.

#define GpsBuffer ( )    GpsLink(ChAvailable())

Definition at line 71 of file gps_ubx.h.

#define GpsEvent (   _sol_available_callback)
Value:
{ \
if (GpsBuffer()) { \
} \
if (gps_ubx.msg_class == UBX_NAV_ID && \
(gps_ubx.msg_id == UBX_NAV_VELNED_ID || \
(gps_ubx.msg_id == UBX_NAV_SOL_ID && \
gps_ubx.have_velned == 0))) { \
if (gps.fix == GPS_FIX_3D) { \
} \
_sol_available_callback(); \
} \
} \
}
uint32_t last_fix_time
cpu time in sec at last valid fix
Definition: gps.h:85
bool_t msg_available
Definition: gps_ubx.h:43
uint8_t fix
status of fix
Definition: gps.h:77
#define GPS_FIX_3D
Definition: gps.h:42
#define FALSE
Definition: imu_chimu.h:141
void gps_ubx_read_message(void)
Definition: gps_ubx.c:92
uint8_t msg_class
Definition: gps_ubx.h:46
uint32_t last_fix_ticks
cpu time in ticks at last valid fix
Definition: gps.h:84
#define gps_ubx_ucenter_event()
Definition: gps_ubx.h:74
#define GpsBuffer()
Definition: gps_ubx.h:71
volatile uint32_t nb_sec_rem
remainder of second in CPU_TICKS
Definition: sys_time.h:56
struct GpsUbx gps_ubx
Definition: gps_ubx.c:81
uint8_t have_velned
Definition: gps_ubx.h:58
volatile uint32_t nb_sec
full seconds since startup
Definition: sys_time.h:55
#define ReadGpsBuffer()
Definition: gps_ubx.h:103
struct GpsState gps
global GPS state
Definition: gps.c:31
uint8_t msg_id
Definition: gps_ubx.h:45

Definition at line 82 of file gps_ubx.h.

#define GpsLink (   _x)    _GpsLink(GPS_LINK, _x)

Definition at line 69 of file gps_ubx.h.

#define ReadGpsBuffer ( )
Value:
{ \
while (GpsLink(ChAvailable())&&!gps_ubx.msg_available) \
gps_ubx_parse(GpsLink(Getch())); \
}
bool_t msg_available
Definition: gps_ubx.h:43
#define GpsLink(_x)
Definition: gps_ubx.h:69
void gps_ubx_parse(uint8_t c)
Definition: gps_ubx.c:193
struct GpsUbx gps_ubx
Definition: gps_ubx.c:81

Definition at line 103 of file gps_ubx.h.

Function Documentation

void ubxsend_cfg_rst ( uint16_t  ,
uint8_t   
)

Definition at line 277 of file gps_ubx.c.

Variable Documentation