Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
gps.h
Go to the documentation of this file.
1/*
2 * Copyright (C) 2003-2011 The Paparazzi Team
3 *
4 * This file is part of paparazzi.
5 *
6 * paparazzi is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License as published by
8 * the Free Software Foundation; either version 2, or (at your option)
9 * any later version.
10 *
11 * paparazzi is distributed in the hope that it will be useful,
12 * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 * GNU General Public License for more details.
15 *
16 * You should have received a copy of the GNU General Public License
17 * along with paparazzi; see the file COPYING. If not, write to
18 * the Free Software Foundation, 59 Temple Place - Suite 330,
19 * Boston, MA 02111-1307, USA.
20 */
21
27#ifndef GPS_H
28#define GPS_H
29
30#ifdef __cplusplus
31extern "C" {
32#endif
33
34#include "std.h"
38
39#include "mcu_periph/sys_time.h"
40#include "generated/airframe.h"
41
42#define GPS_FIX_NONE 0x00
43#define GPS_FIX_2D 0x02
44#define GPS_FIX_3D 0x03
45#define GPS_FIX_DGPS 0x04
46#define GPS_FIX_RTK 0x05
47
48#define GPS_VALID_POS_ECEF_BIT 0
49#define GPS_VALID_POS_LLA_BIT 1
50#define GPS_VALID_POS_UTM_BIT 2
51#define GPS_VALID_VEL_ECEF_BIT 3
52#define GPS_VALID_VEL_NED_BIT 4
53#define GPS_VALID_HMSL_BIT 5
54#define GPS_VALID_COURSE_BIT 6
55
56#ifndef GPS_NB_CHANNELS
57#define GPS_NB_CHANNELS 40
58#endif
59
60#define GPS_MODE_AUTO 0
61#define GPS_MODE_PRIMARY 1
62#define GPS_MODE_SECONDARY 2
63
64#ifndef MULTI_GPS_MODE
65#define MULTI_GPS_MODE GPS_MODE_AUTO
66#endif
67
68/* expand GpsId(PRIMARY_GPS) to e.g. GPS_UBX_ID */
69#define __GpsId(_x) _x ## _ID
70#define _GpsId(_x) __GpsId(_x)
71#define GpsId(_x) _GpsId(_x)
72
73
75
85
120
127
140
142extern struct GpsState gps;
143
144#ifdef GPS_TYPE_H
145#include GPS_TYPE_H
146#endif
147#ifdef GPS_SECONDARY_TYPE_H
148#include GPS_SECONDARY_TYPE_H
149#endif
150
152extern void gps_init(void);
153
155extern void gps_inject_data(uint8_t packet_id, uint8_t length, uint8_t *data);
156
157extern void gps_parse_GPS_INJECT(uint8_t *buf);
158extern void gps_parse_RTCM_INJECT(uint8_t *buf);
159
165extern bool gps_fix_valid(void);
166
167// Compatibility macros
168#define GpsFixValid() gps_fix_valid()
169#if USE_GPS
170#define GpsIsLost() !GpsFixValid()
171#endif
172
176#ifndef GPS_TIMEOUT
177#define GPS_TIMEOUT 2
178#endif
179
183extern void gps_periodic_check(struct GpsState *gps_s);
184
185// FIXME not used, to be removed ?
186static inline bool gps_has_been_good(void)
187{
188 static bool gps_had_valid_fix = false;
189 if (GpsFixValid()) {
190 gps_had_valid_fix = true;
191 }
192 return gps_had_valid_fix;
193}
194
196static inline float gps_time_since_last_3dfix(void)
197{
199}
200
201
202/*
203 * For GPS time synchronizaiton...
204 */
205extern struct GpsTimeSync gps_time_sync;
206
213
220extern struct LlaCoor_f lla_float_from_gps(struct GpsState *gps_s);
221
228extern struct LlaCoor_i lla_int_from_gps(struct GpsState *gps_s);
229
236extern struct EcefCoor_f ecef_float_from_gps(struct GpsState *gps_s);
237
244extern struct EcefCoor_i ecef_int_from_gps(struct GpsState *gps_s);
245
252extern struct EcefCoor_f ecef_vel_float_from_gps(struct GpsState *gps_s);
253
260extern struct EcefCoor_i ecef_vel_int_from_gps(struct GpsState *gps_s);
261
268extern struct NedCoor_f ned_vel_float_from_gps(struct GpsState *gps_s);
269
276extern struct NedCoor_i ned_vel_int_from_gps(struct GpsState *gps_s);
277
285extern struct UtmCoor_f utm_float_from_gps(struct GpsState *gps_s, uint8_t zone);
286
294extern struct UtmCoor_i utm_int_from_gps(struct GpsState *gps_s, uint8_t zone);
295
303extern uint16_t gps_day_number(uint16_t year, uint8_t month, uint8_t day);
304
312extern uint16_t gps_week_number(uint16_t year, uint8_t month, uint8_t day);
313
314#ifdef __cplusplus
315}
316#endif
317
318#endif /* GPS_H */
int16_t azim
azimuth in deg
Definition gps.h:83
uint8_t multi_gps_mode
Definition gps.c:82
uint32_t tow
GPS time of week in ms.
Definition gps.h:109
float distance_acc
Distance accuracy in meters.
Definition gps.h:137
uint8_t qi
quality bitfield (GPS receiver specific)
Definition gps.h:80
int32_t hmsl
height above mean sea level (MSL) in mm
Definition gps.h:94
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.
Definition gps.c:577
static float gps_time_since_last_3dfix(void)
Returns the time since last 3D fix in seconds (float)
Definition gps.h:196
struct NedCoor_f ned_vel_float_from_gps(struct GpsState *gps_s)
Get GPS ned velocity (float) Converted on the fly if not available.
Definition gps.c:544
int8_t elev
elevation in deg
Definition gps.h:82
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
Definition gps.h:92
float heading
Relative heading to the reference station in radians.
Definition gps.h:134
uint32_t sacc
speed accuracy in cm/s
Definition gps.h:103
struct UtmCoor_i utm_pos
position in UTM (north,east: cm; alt: mm over MSL)
Definition gps.h:93
uint32_t cacc
course accuracy in rad*1e7
Definition gps.h:104
int32_t course
GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
Definition gps.h:99
int32_t t0_tow_frac
fractional ns remainder of tow [ms], range -500000 .. 500000
Definition gps.h:124
uint8_t cno
Carrier to Noise Ratio (Signal Strength) in dbHz.
Definition gps.h:81
struct EcefCoor_f ecef_vel_float_from_gps(struct GpsState *gps_s)
Get GPS ecef velocity (float) Converted on the fly if not available.
Definition gps.c:509
float heading_acc
Heading accuracy in radians.
Definition gps.h:138
struct EcefCoor_i ecef_pos
position in ECEF in cm
Definition gps.h:91
struct GpsTimeSync gps_time_sync
Definition gps.c:75
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.
Definition gps.c:602
uint32_t hacc
horizontal accuracy in cm
Definition gps.h:101
uint16_t gps_week_number(uint16_t year, uint8_t month, uint8_t day)
Number of weeks since navigation epoch (6 January 1980)
Definition gps.c:649
void gps_parse_GPS_INJECT(uint8_t *buf)
Definition gps.c:424
double distance
Relative distance to the reference station in meters.
Definition gps.h:133
uint32_t last_3dfix_ticks
cpu time ticks at last valid 3D fix
Definition gps.h:114
struct GpsState gps
global GPS state
Definition gps.c:74
struct LlaCoor_i lla_int_from_gps(struct GpsState *gps_s)
Get GPS lla (integer) Converted on the fly if not available.
Definition gps.c:464
struct EcefCoor_i ecef_vel_int_from_gps(struct GpsState *gps_s)
Get GPS ecef velocity (integer) Converted on the fly if not available.
Definition gps.c:522
struct EcefCoor_i ecef_vel
speed ECEF in cm/s
Definition gps.h:95
uint32_t t0_ticks
hw clock ticks when GPS message is received
Definition gps.h:125
struct EcefCoor_f ecef_float_from_gps(struct GpsState *gps_s)
Get GPS ecef pos (float) Converted on the fly if not available.
Definition gps.c:480
#define GPS_NB_CHANNELS
Definition gps.h:57
void gps_parse_RTCM_INJECT(uint8_t *buf)
Definition gps.c:437
uint16_t pdop
position dilution of precision scaled by 100
Definition gps.h:105
uint32_t tow
Time of week (GPS) in ms.
Definition gps.h:130
struct NedCoor_i ned_vel
speed NED in cm/s
Definition gps.h:96
uint32_t last_msg_time
cpu time in sec at last received GPS message
Definition gps.h:117
uint32_t t0_tow
GPS time of week in ms from last message.
Definition gps.h:123
void gps_inject_data(uint8_t packet_id, uint8_t length, uint8_t *data)
GPS packet injection (default empty)
Definition gps.c:418
uint8_t svid
Satellite ID.
Definition gps.h:78
uint8_t nb_channels
Number of scanned satellites.
Definition gps.h:111
struct NedCoor_f pos_acc
Position accuracy in meters.
Definition gps.h:136
uint32_t last_3dfix_time
cpu time in sec at last valid 3D fix
Definition gps.h:115
uint32_t pacc
position accuracy in cm
Definition gps.h:100
struct EcefCoor_i ecef_int_from_gps(struct GpsState *gps_s)
Get GPS ecef pos (integer) Converted on the fly if not available.
Definition gps.c:493
uint16_t gspeed
norm of 2d ground speed in cm/s
Definition gps.h:97
uint8_t valid_fields
bitfield indicating valid fields (GPS_VALID_x_BIT)
Definition gps.h:88
uint8_t comp_id
id of current gps
Definition gps.h:89
struct NedCoor_i ned_vel_int_from_gps(struct GpsState *gps_s)
Get GPS ned velocity (integer) Converted on the fly if not available.
Definition gps.c:557
struct LlaCoor_f lla_float_from_gps(struct GpsState *gps_s)
Get GPS lla (float) Converted on the fly if not available.
Definition gps.c:451
uint32_t vacc
vertical accuracy in cm
Definition gps.h:102
#define GpsFixValid()
Definition gps.h:168
void gps_init(void)
initialize the global GPS state
Definition gps.c:350
struct NedCoor_d pos
Relative postion to the reference station in meters.
Definition gps.h:132
uint16_t speed_3d
norm of 3d speed in cm/s
Definition gps.h:98
uint32_t gps_tow_from_sys_ticks(uint32_t sys_ticks)
Convert time in sys_time ticks to GPS time of week.
Definition gps.c:393
uint16_t gps_day_number(uint16_t year, uint8_t month, uint8_t day)
Number of days since navigation epoch (6 January 1980)
Definition gps.c:639
bool gps_fix_valid(void)
Check if GPS fix is valid.
Definition gps.c:295
struct SVinfo svinfos[GPS_NB_CHANNELS]
holds information from the Space Vehicles (Satellites)
Definition gps.h:112
static bool gps_has_been_good(void)
Definition gps.h:186
void gps_periodic_check(struct GpsState *gps_s)
Periodic GPS check.
Definition gps.c:279
uint8_t flags
bitfield with GPS receiver specific flags
Definition gps.h:79
uint16_t reset
hotstart, warmstart, coldstart
Definition gps.h:118
uint32_t last_msg_ticks
cpu time ticks at last received GPS message
Definition gps.h:116
uint16_t reference_id
Reference station identification.
Definition gps.h:129
uint8_t num_sv
number of sat in fix
Definition gps.h:106
uint16_t week
GPS week.
Definition gps.h:108
uint8_t fix
status of fix
Definition gps.h:107
data structure for GPS information
Definition gps.h:87
data structure for GPS time sync
Definition gps.h:122
data structure for Space Vehicle Information of a single satellite
Definition gps.h:77
vector in North East Down coordinates Units: meters
uint8_t zone
UTM zone number.
vector in EarthCenteredEarthFixed coordinates
vector in Latitude, Longitude and Altitude
vector in North East Down coordinates
position in UTM coordinates
uint16_t foo
Definition main_demo5.c:58
Paparazzi double-precision floating point math for geodetic calculations.
Paparazzi floating point math for geodetic calculations.
uint8_t zone
UTM zone number.
vector in EarthCenteredEarthFixed coordinates
vector in Latitude, Longitude and Altitude
vector in North East Down coordinates Units: meters
position in UTM coordinates Units: meters
Paparazzi fixed point math for geodetic calculations.
Architecture independent timing functions.
uint32_t cpu_ticks_per_sec
cpu ticks per second
Definition sys_time.h:80
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
short int16_t
Typedef defining 16 bit short type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
signed char int8_t
Typedef defining 8 bit char type.