Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
gps.h File Reference

Device independent GPS code (interface) More...

#include "std.h"
#include "math/pprz_geodetic_int.h"
#include "math/pprz_geodetic_float.h"
#include "mcu_periph/sys_time.h"
+ Include dependency graph for gps.h:

Go to the source code of this file.

Data Structures

struct  SVinfo
 data structure for Space Vehicle Information of a single satellite More...
 
struct  GpsState
 data structure for GPS information More...
 
struct  GpsTimeSync
 data structure for GPS time sync More...
 
struct  GpsRelposNED
 data structures for GPS with RTK capabilities More...
 
struct  RtcmMan
 

Macros

#define GPS_FIX_NONE   0x00
 No GPS fix. More...
 
#define GPS_FIX_2D   0x02
 2D GPS fix More...
 
#define GPS_FIX_3D   0x03
 3D GPS fix More...
 
#define GPS_FIX_DGPS   0x04
 DGPS fix. More...
 
#define GPS_FIX_RTK   0x05
 RTK GPS fix. More...
 
#define GpsFixValid()   (gps.fix >= GPS_FIX_3D)
 
#define GpsIsLost()   !GpsFixValid()
 
#define GPS_VALID_POS_ECEF_BIT   0
 
#define GPS_VALID_POS_LLA_BIT   1
 
#define GPS_VALID_POS_UTM_BIT   2
 
#define GPS_VALID_VEL_ECEF_BIT   3
 
#define GPS_VALID_VEL_NED_BIT   4
 
#define GPS_VALID_HMSL_BIT   5
 
#define GPS_VALID_COURSE_BIT   6
 
#define GPS_NB_CHANNELS   40
 
#define GPS_MODE_AUTO   0
 
#define GPS_MODE_PRIMARY   1
 
#define GPS_MODE_SECONDARY   2
 
#define MULTI_GPS_MODE   GPS_MODE_AUTO
 
#define __GpsId(_x)   _x ## _ID
 
#define _GpsId(_x)   __GpsId(_x)
 
#define GpsId(_x)   _GpsId(_x)
 
#define GPS_TIMEOUT   2
 GPS timeout in seconds. More...
 

Functions

void gps_init (void)
 initialize the global GPS state More...
 
void gps_inject_data (uint8_t packet_id, uint8_t length, uint8_t *data)
 GPS packet injection (default empty) More...
 
static bool gps_has_been_good (void)
 
void gps_periodic_check (struct GpsState *gps_s)
 Periodic GPS check. More...
 
uint32_t gps_tow_from_sys_ticks (uint32_t sys_ticks)
 Convert time in sys_time ticks to GPS time of week. More...
 
struct UtmCoor_f utm_float_from_gps (struct GpsState *gps_s, uint8_t zone)
 Convenience function to get utm position in float from GPS structure. More...
 
struct UtmCoor_i utm_int_from_gps (struct GpsState *gps_s, uint8_t zone)
 Convenience function to get utm position in int from GPS structure. More...
 
uint16_t gps_day_number (uint16_t year, uint8_t month, uint8_t day)
 Number of days since navigation epoch (6 January 1980) More...
 
uint16_t gps_week_number (uint16_t year, uint8_t month, uint8_t day)
 Number of weeks since navigation epoch (6 January 1980) More...
 

Variables

uint8_t multi_gps_mode
 
struct GpsState gps
 global GPS state More...
 
struct GpsTimeSync gps_time_sync
 

Detailed Description

Device independent GPS code (interface)

Definition in file gps.h.


Data Structure Documentation

◆ SVinfo

struct SVinfo

data structure for Space Vehicle Information of a single satellite

Definition at line 77 of file gps.h.

Data Fields
int16_t azim azimuth in deg
uint8_t cno Carrier to Noise Ratio (Signal Strength) in dbHz.
int8_t elev elevation in deg
uint8_t flags bitfield with GPS receiver specific flags
uint8_t qi quality bitfield (GPS receiver specific)
uint8_t svid Satellite ID.

◆ GpsState

struct GpsState

data structure for GPS information

Definition at line 87 of file gps.h.

+ Collaboration diagram for GpsState:
Data Fields
uint32_t cacc course accuracy in rad*1e7
uint8_t comp_id id of current gps
int32_t course GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
struct EcefCoor_i ecef_pos position in ECEF in cm
struct EcefCoor_i ecef_vel speed ECEF in cm/s
uint8_t fix status of fix
uint16_t gspeed norm of 2d ground speed in cm/s
uint32_t hacc horizontal accuracy in cm
int32_t hmsl height above mean sea level (MSL) in mm
uint32_t last_3dfix_ticks cpu time ticks at last valid 3D fix
uint32_t last_3dfix_time cpu time in sec at last valid 3D fix
uint32_t last_msg_ticks cpu time ticks at last received GPS message
uint32_t last_msg_time cpu time in sec at last received GPS message
struct LlaCoor_i lla_pos position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
uint8_t nb_channels Number of scanned satellites.
struct NedCoor_i ned_vel speed NED in cm/s
uint8_t num_sv number of sat in fix
uint32_t pacc position accuracy in cm
uint16_t pdop position dilution of precision scaled by 100
uint16_t reset hotstart, warmstart, coldstart
uint32_t sacc speed accuracy in cm/s
uint16_t speed_3d norm of 3d speed in cm/s
struct SVinfo svinfos[GPS_NB_CHANNELS] holds information from the Space Vehicles (Satellites)
uint32_t tow GPS time of week in ms.
struct UtmCoor_i utm_pos position in UTM (north,east: cm; alt: mm over MSL)
uint32_t vacc vertical accuracy in cm
uint8_t valid_fields bitfield indicating valid fields (GPS_VALID_x_BIT)
uint16_t week GPS week.

◆ GpsTimeSync

struct GpsTimeSync

data structure for GPS time sync

Definition at line 122 of file gps.h.

Data Fields
uint32_t t0_ticks hw clock ticks when GPS message is received
uint32_t t0_tow GPS time of week in ms from last message.
int32_t t0_tow_frac fractional ns remainder of tow [ms], range -500000 .. 500000

◆ GpsRelposNED

struct GpsRelposNED

data structures for GPS with RTK capabilities

Definition at line 129 of file gps.h.

Data Fields
uint32_t accD
uint32_t accE
uint32_t accN
uint8_t carrSoln
uint8_t diffSoln
uint8_t gnssFixOK
uint32_t iTOW
uint16_t refStationId
int32_t relPosD
int32_t relPosE
int8_t relPosHPD
int8_t relPosHPE
int8_t relPosHPN
int32_t relPosN
uint8_t relPosValid

◆ RtcmMan

struct RtcmMan

Definition at line 147 of file gps.h.

Data Fields
uint32_t Cnt105
uint32_t Cnt177
uint32_t Cnt187
uint32_t Crc105
uint32_t Crc177
uint32_t Crc187
uint16_t MsgType
uint16_t RefStation

Macro Definition Documentation

◆ __GpsId

#define __GpsId (   _x)    _x ## _ID

Definition at line 69 of file gps.h.

◆ _GpsId

#define _GpsId (   _x)    __GpsId(_x)

Definition at line 70 of file gps.h.

◆ GPS_FIX_2D

#define GPS_FIX_2D   0x02

2D GPS fix

Definition at line 38 of file gps.h.

◆ GPS_FIX_3D

#define GPS_FIX_3D   0x03

3D GPS fix

Definition at line 39 of file gps.h.

◆ GPS_FIX_DGPS

#define GPS_FIX_DGPS   0x04

DGPS fix.

Definition at line 40 of file gps.h.

◆ GPS_FIX_NONE

#define GPS_FIX_NONE   0x00

No GPS fix.

Definition at line 37 of file gps.h.

◆ GPS_FIX_RTK

#define GPS_FIX_RTK   0x05

RTK GPS fix.

Definition at line 41 of file gps.h.

◆ GPS_MODE_AUTO

#define GPS_MODE_AUTO   0

Definition at line 60 of file gps.h.

◆ GPS_MODE_PRIMARY

#define GPS_MODE_PRIMARY   1

Definition at line 61 of file gps.h.

◆ GPS_MODE_SECONDARY

#define GPS_MODE_SECONDARY   2

Definition at line 62 of file gps.h.

◆ GPS_NB_CHANNELS

#define GPS_NB_CHANNELS   40

Definition at line 57 of file gps.h.

◆ GPS_TIMEOUT

#define GPS_TIMEOUT   2

GPS timeout in seconds.

Definition at line 176 of file gps.h.

◆ GPS_VALID_COURSE_BIT

#define GPS_VALID_COURSE_BIT   6

Definition at line 54 of file gps.h.

◆ GPS_VALID_HMSL_BIT

#define GPS_VALID_HMSL_BIT   5

Definition at line 53 of file gps.h.

◆ GPS_VALID_POS_ECEF_BIT

#define GPS_VALID_POS_ECEF_BIT   0

Definition at line 48 of file gps.h.

◆ GPS_VALID_POS_LLA_BIT

#define GPS_VALID_POS_LLA_BIT   1

Definition at line 49 of file gps.h.

◆ GPS_VALID_POS_UTM_BIT

#define GPS_VALID_POS_UTM_BIT   2

Definition at line 50 of file gps.h.

◆ GPS_VALID_VEL_ECEF_BIT

#define GPS_VALID_VEL_ECEF_BIT   3

Definition at line 51 of file gps.h.

◆ GPS_VALID_VEL_NED_BIT

#define GPS_VALID_VEL_NED_BIT   4

Definition at line 52 of file gps.h.

◆ GpsFixValid

#define GpsFixValid ( )    (gps.fix >= GPS_FIX_3D)

Definition at line 43 of file gps.h.

◆ GpsId

#define GpsId (   _x)    _GpsId(_x)

Definition at line 71 of file gps.h.

◆ GpsIsLost

#define GpsIsLost ( )    !GpsFixValid()

Definition at line 45 of file gps.h.

◆ MULTI_GPS_MODE

#define MULTI_GPS_MODE   GPS_MODE_AUTO

Definition at line 65 of file gps.h.

Function Documentation

◆ gps_day_number()

uint16_t gps_day_number ( uint16_t  year,
uint8_t  month,
uint8_t  day 
)

Number of days since navigation epoch (6 January 1980)

Parameters
[in]yearcurrent year
[in]monthcurrent month
[in]daycurrent day
Returns
number of days since navigation epoch

Definition at line 452 of file gps.c.

References month_days.

Referenced by gps_week_number().

+ Here is the caller graph for this function:

◆ gps_has_been_good()

static bool gps_has_been_good ( void  )
inlinestatic

Definition at line 179 of file gps.h.

References GpsFixValid.

◆ gps_init()

◆ gps_inject_data()

void gps_inject_data ( uint8_t  packet_id,
uint8_t  length,
uint8_t data 
)

GPS packet injection (default empty)

GPS packet injection (default empty)

Definition at line 408 of file gps_piksi.c.

References gps_piksi_write(), and sbp_state.

Referenced by dl_parse_msg().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ gps_periodic_check()

void gps_periodic_check ( struct GpsState gps_s)

Periodic GPS check.

Marks GPS as lost when no GPS message was received for GPS_TIMEOUT seconds

Definition at line 264 of file gps.c.

References GpsState::comp_id, GpsState::fix, gps, GPS_FIX_NONE, GPS_TIMEOUT, GpsState::last_msg_time, and sys_time::nb_sec.

Referenced by dw1000_arduino_periodic(), and intermcu_periodic().

+ Here is the caller graph for this function:

◆ gps_tow_from_sys_ticks()

uint32_t gps_tow_from_sys_ticks ( uint32_t  sys_ticks)

Convert time in sys_time ticks to GPS time of week.

The resolution is sys_time.resolution

Returns
GPS tow in ms

Definition at line 355 of file gps.c.

References gps_time_sync, msec_of_sys_time_ticks(), MSEC_PER_WEEK, GpsTimeSync::t0_ticks, and GpsTimeSync::t0_tow.

Referenced by acInfoSetPositionEnu_f(), acInfoSetPositionEnu_i(), acInfoSetPositionLla_f(), acInfoSetPositionLla_i(), acInfoSetPositionUtm_f(), acInfoSetPositionUtm_i(), acInfoSetVelocityEnu_f(), acInfoSetVelocityEnu_i(), parse_acinfo_dl(), trigger_ext_periodic(), and windturbine_periodic().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ gps_week_number()

uint16_t gps_week_number ( uint16_t  year,
uint8_t  month,
uint8_t  day 
)

Number of weeks since navigation epoch (6 January 1980)

Parameters
[in]yearcurrent year
[in]monthcurrent month
[in]daycurrent day
Returns
number of weeks since navigation epoch

Definition at line 462 of file gps.c.

References gps_day_number().

Referenced by gps_ubx_parse_nav_pvt().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ utm_float_from_gps()

struct UtmCoor_f utm_float_from_gps ( struct GpsState gps_s,
uint8_t  zone 
)

Convenience function to get utm position in float from GPS structure.

Beware that altitude is initialized to zero but not set to the correct value

Parameters
[in]gps_spointer to the gps structure
[in]zoneset the utm zone in which the position should be computed, 0 to try to get it automatically from lla position
Returns
utm position in float, altitude hmsl.

Convenience function to get utm position in float from GPS structure.

Definition at line 390 of file gps.c.

References UtmCoor_f::alt, UtmCoor_f::east, GPS_VALID_HMSL_BIT, GPS_VALID_POS_LLA_BIT, GPS_VALID_POS_UTM_BIT, UTM_FLOAT_OF_BFP, utm_of_lla_i(), wgs84_ellipsoid_to_geoid_i(), UtmCoor_f::zone, and UtmCoor_i::zone.

Referenced by gps_cb(), ins_alt_float_update_gps(), ins_float_invariant_update_gps(), and ins_reset_local_origin().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ utm_int_from_gps()

struct UtmCoor_i utm_int_from_gps ( struct GpsState gps_s,
uint8_t  zone 
)

Convenience function to get utm position in int from GPS structure.

Beware that altitude is initialized to zero but not set to the correct value

Parameters
[in]gps_spointer to the gps structure
[in]zoneset the utm zone in which the position should be computed, 0 to try to get it automatically from lla position
Returns
utm position in fixed point (cm), altitude hmsl (mm).

Definition at line 415 of file gps.c.

References UtmCoor_i::alt, UtmCoor_i::east, GPS_VALID_HMSL_BIT, GPS_VALID_POS_LLA_BIT, GPS_VALID_POS_UTM_BIT, UTM_COPY, utm_of_lla_i(), wgs84_ellipsoid_to_geoid_i(), and UtmCoor_i::zone.

Referenced by send_gps().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

Variable Documentation

◆ gps

◆ gps_time_sync

struct GpsTimeSync gps_time_sync

Definition at line 70 of file gps.c.

Referenced by gps_cb(), and gps_tow_from_sys_ticks().

◆ multi_gps_mode

uint8_t multi_gps_mode

Definition at line 78 of file gps.c.

Referenced by gps_init().