Paparazzi UAS  v5.10_stable-5-g83a0da5-dirty
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
gps_piksi.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Gautier Hattenberger <gautier.hattenberger@enac.fr>
3  * 2015 Freek van Tienen <freek.v.tienen@gmail.com>
4  *
5  * This file is part of paparazzi.
6  *
7  * paparazzi is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2, or (at your option)
10  * any later version.
11  *
12  * paparazzi is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with paparazzi; see the file COPYING. If not, write to
19  * the Free Software Foundation, 59 Temple Place - Suite 330,
20  * Boston, MA 02111-1307, USA.
21  *
22  */
23 
34 #include "subsystems/gps.h"
35 #include "subsystems/abi.h"
36 #include "mcu_periph/uart.h"
38 
39 // get NAV_MSL0 for geoid separation
40 #include "generated/flight_plan.h"
41 
42 #include <libsbp/sbp.h>
43 #include <libsbp/navigation.h>
44 #include <libsbp/observation.h>
45 #include <libsbp/tracking.h>
46 #include <libsbp/system.h>
47 #include <libsbp/settings.h>
48 #include <libsbp/piksi.h>
49 
50 #define SBP_FIX_MODE_SPP 0X00
51 #define SBP_FIX_MODE_FLOAT 0X02
52 #define SPB_FIX_MODE_FIXED 0X01
53 
54 #define POS_ECEF_TIMEOUT 1000
55 
56 /*
57  * implementation specific gps state
58  */
61 
63 
64 #if PERIODIC_TELEMETRY
66 
67 static void send_piksi_heartbeat(struct transport_tx *trans, struct link_device *dev)
68 {
69  pprz_msg_send_PIKSI_HEARTBEAT(trans, dev, AC_ID,
71 }
72 
73 #endif
74 
75 /*
76  * Set the Piksi GPS antenna (default is Patch, internal)
77  */
78 #if USE_PIKSI_EXT_ANTENNA
79 static const char SBP_ANT_SET[] = "frontend""\x00""antenna_selection""\x00""External";
80 #elif USE_PIKSI_AUTO_ANTENNA
81 static const char SBP_ANT_SET[] = "frontend""\x00""antenna_selection""\x00""Auto";
82 #else
83 static const char SBP_ANT_SET[] = "frontend""\x00""antenna_selection""\x00""Patch";
84 #endif
85 
86 /*
87  * Set the UART config depending on which UART is connected
88  */
89 #if USE_PIKSI_UARTA
90 static const char SBP_UART_SET1[] = "uart_uarta""\x00""mode""\x00""SBP";
91 static const char SBP_UART_SET2[] = "uart_uarta""\x00""sbp_message_mask""\x00""784"; //0x310 which masks all navigation and tracking messages
92 static const char SBP_UART_SET3[] = "uart_uarta""\x00""configure_telemetry_radio_on_boot""\x00""False";
93 #else
94 static const char SBP_UART_SET1[] = "uart_uartb""\x00""mode""\x00""SBP";
95 static const char SBP_UART_SET2[] = "uart_uartb""\x00""sbp_message_mask""\x00""784"; //0x310 which masks all navigation and tracking messages
96 static const char SBP_UART_SET3[] = "uart_uartb""\x00""configure_telemetry_radio_on_boot""\x00""False";
97 #endif
98 
99 /*
100  * State of the SBP message parser.
101  * Must be statically allocated.
102  */
103 sbp_state_t sbp_state;
104 
105 /*
106  * SBP callback nodes must be statically allocated. Each message ID / callback
107  * pair must have a unique sbp_msg_callbacks_node_t associated with it.
108  */
109 sbp_msg_callbacks_node_t pos_ecef_node;
110 sbp_msg_callbacks_node_t vel_ecef_node;
111 sbp_msg_callbacks_node_t pos_llh_node;
112 sbp_msg_callbacks_node_t vel_ned_node;
113 sbp_msg_callbacks_node_t dops_node;
114 sbp_msg_callbacks_node_t gps_time_node;
115 sbp_msg_callbacks_node_t tracking_state_node;
116 sbp_msg_callbacks_node_t tracking_state_dep_a_node;
117 sbp_msg_callbacks_node_t heartbeat_node;
118 
119 
120 static void gps_piksi_publish(void);
121 static uint8_t get_fix_mode(uint8_t flags);
122 uint32_t gps_piksi_read(uint8_t *buff, uint32_t n, void *context __attribute__((unused)));
123 uint32_t gps_piksi_write(uint8_t *buff, uint32_t n, void *context __attribute__((unused)));
125 
126 /*
127  * Callback functions to interpret SBP messages.
128  * Every message ID has a callback associated with it to
129  * receive and interpret the message payload.
130  */
131 static void sbp_pos_ecef_callback(uint16_t sender_id __attribute__((unused)),
132  uint8_t len __attribute__((unused)),
133  uint8_t msg[],
134  void *context __attribute__((unused)))
135 {
136  time_since_last_pos_update = get_sys_time_msec();
137  msg_pos_ecef_t pos_ecef = *(msg_pos_ecef_t *)msg;
138 
139  // Check if we got RTK fix (FIXME when libsbp has a nicer way of doing this)
140  gps_piksi.fix = get_fix_mode(pos_ecef.flags);
141  // get_fix_mode() will still return fix > 3D even if the current flags are spp so ignore when it is spp
142  if ( ( (gps_piksi.fix > GPS_FIX_3D) )
143  && pos_ecef.flags == SBP_FIX_MODE_SPP) {
144  return;
145  }
146 
147  gps_piksi.ecef_pos.x = (int32_t)(pos_ecef.x * 100.0);
148  gps_piksi.ecef_pos.y = (int32_t)(pos_ecef.y * 100.0);
149  gps_piksi.ecef_pos.z = (int32_t)(pos_ecef.z * 100.0);
151  gps_piksi.pacc = (uint32_t)(pos_ecef.accuracy);// FIXME not implemented yet by libswiftnav
152  gps_piksi.num_sv = pos_ecef.n_sats;
153  gps_piksi.tow = pos_ecef.tow;
154  gps_piksi_publish(); // Only if RTK position
155 }
156 
157 static void sbp_vel_ecef_callback(uint16_t sender_id __attribute__((unused)),
158  uint8_t len __attribute__((unused)),
159  uint8_t msg[],
160  void *context __attribute__((unused)))
161 {
162  msg_vel_ecef_t vel_ecef = *(msg_vel_ecef_t *)msg;
163  gps_piksi.ecef_vel.x = (int32_t)(vel_ecef.x / 10);
164  gps_piksi.ecef_vel.y = (int32_t)(vel_ecef.y / 10);
165  gps_piksi.ecef_vel.z = (int32_t)(vel_ecef.z / 10);
167  gps_piksi.sacc = (uint32_t)(vel_ecef.accuracy);
168 
169  // Solution available (VEL_ECEF is the last message to be send)
170  gps_piksi_publish(); // TODO: filter out if got RTK position
171 }
172 
173 static void sbp_pos_llh_callback(uint16_t sender_id __attribute__((unused)),
174  uint8_t len __attribute__((unused)),
175  uint8_t msg[],
176  void *context __attribute__((unused)))
177 {
178  static uint8_t last_flags = 0;
179  msg_pos_llh_t pos_llh = *(msg_pos_llh_t *)msg;
180 
181  // Check if we got RTK fix (FIXME when libsbp has a nicer way of doing this)
182  if (pos_llh.flags > 0 || last_flags == 0) {
183  gps_piksi.lla_pos.lat = (int32_t)(pos_llh.lat * 1e7);
184  gps_piksi.lla_pos.lon = (int32_t)(pos_llh.lon * 1e7);
185 
186  int32_t alt = (int32_t)(pos_llh.height * 1000.);
187  // height is above ellipsoid or MSL according to bit flag (but not both are available)
188  // 0: above ellipsoid
189  // 1: above MSL
190  // we have to get the HMSL from the flight plan for now
191  if (bit_is_set(pos_llh.flags, 3)) {
192  gps_piksi.hmsl = alt;
193  gps_piksi.lla_pos.alt = alt + NAV_MSL0;
194  } else {
195  gps_piksi.lla_pos.alt = alt;
196  gps_piksi.hmsl = alt - NAV_MSL0;
197  }
198 
201  }
202  last_flags = pos_llh.flags;
203 }
204 
205 static void sbp_vel_ned_callback(uint16_t sender_id __attribute__((unused)),
206  uint8_t len __attribute__((unused)),
207  uint8_t msg[],
208  void *context __attribute__((unused)))
209 {
210  msg_vel_ned_t vel_ned = *(msg_vel_ned_t *)msg;
211  gps_piksi.ned_vel.x = (int32_t)(vel_ned.n / 10);
212  gps_piksi.ned_vel.y = (int32_t)(vel_ned.e / 10);
213  gps_piksi.ned_vel.z = (int32_t)(vel_ned.d / 10);
215 
219 }
220 
221 static void sbp_dops_callback(uint16_t sender_id __attribute__((unused)),
222  uint8_t len __attribute__((unused)),
223  uint8_t msg[],
224  void *context __attribute__((unused)))
225 {
226  msg_dops_t dops = *(msg_dops_t *)msg;
227  gps_piksi.pdop = dops.pdop;
228 }
229 
230 static void sbp_gps_time_callback(uint16_t sender_id __attribute__((unused)),
231  uint8_t len __attribute__((unused)),
232  uint8_t msg[],
233  void *context __attribute__((unused)))
234 {
235  msg_gps_time_t gps_time = *(msg_gps_time_t *)msg;
236  gps_piksi.week = gps_time.wn;
237  gps_piksi.tow = gps_time.tow;
238 }
239 
240 static void sbp_tracking_state_callback(uint16_t sender_id __attribute__((unused)),
241  uint8_t len,
242  uint8_t msg[],
243  void *context __attribute__((unused)))
244 {
245  uint8_t channels_cnt = len/sizeof(tracking_channel_state_t);
246  msg_tracking_state_t *tracking_state = (msg_tracking_state_t *)msg;
247 
248  for(uint8_t i = 0; i < channels_cnt; i++) {
249  if(tracking_state->states[i].state == 1) {
250  gps_piksi.svinfos[i].svid = tracking_state->states[i].sid + 1;
251  gps_piksi.svinfos[i].cno = tracking_state->states[i].cn0;
252  }
253  }
254 }
255 
256 static void sbp_tracking_state_dep_a_callback(uint16_t sender_id __attribute__((unused)),
257  uint8_t len,
258  uint8_t msg[],
259  void *context __attribute__((unused)))
260 {
261  uint8_t channels_cnt = len/sizeof(tracking_channel_state_dep_a_t);
262  msg_tracking_state_dep_a_t *tracking_state = (msg_tracking_state_dep_a_t *)msg;
263 
264  for(uint8_t i = 0; i < channels_cnt; i++) {
265  if(tracking_state->states[i].state == 1) {
266  gps_piksi.svinfos[i].svid = tracking_state->states[i].prn + 1;
267  gps_piksi.svinfos[i].cno = tracking_state->states[i].cn0;
268  }
269  }
270 }
271 
272 static void spb_heartbeat_callback(uint16_t sender_id __attribute__((unused)),
273  uint8_t len __attribute__((unused)),
274  uint8_t msg[] __attribute__((unused)),
275  void *context __attribute__((unused)))
276 {
278 }
279 
280 /*
281  * Return fix mode based on present and past flags
282  */
284 {
285  static uint8_t n_since_last_rtk = 0;
286  if (flags == SBP_FIX_MODE_SPP) {
287  n_since_last_rtk++;
288  if ( n_since_last_rtk > 2 ) {
289  return GPS_FIX_3D;
290  } else {
291  return gps.fix;
292  }
293  } else if (flags == SBP_FIX_MODE_FLOAT) {
294  n_since_last_rtk = 0;
295  return GPS_FIX_DGPS;
296  } else if (flags == SPB_FIX_MODE_FIXED) {
297  n_since_last_rtk = 0;
298  return GPS_FIX_RTK;
299  } else {
300  return GPS_FIX_NONE;
301  }
302 
303 }
304 
305 /*
306  * Initialize the Piksi GPS and write the settings
307  */
308 void gps_piksi_init(void)
309 {
310  /* Setup SBP nodes */
311  sbp_state_init(&sbp_state);
312 
313  /* Register a node and callback, and associate them with a specific message ID. */
314  sbp_register_callback(&sbp_state, SBP_MSG_POS_ECEF, &sbp_pos_ecef_callback, NULL, &pos_ecef_node);
315  sbp_register_callback(&sbp_state, SBP_MSG_VEL_ECEF, &sbp_vel_ecef_callback, NULL, &vel_ecef_node);
316  sbp_register_callback(&sbp_state, SBP_MSG_POS_LLH, &sbp_pos_llh_callback, NULL, &pos_llh_node);
317  sbp_register_callback(&sbp_state, SBP_MSG_VEL_NED, &sbp_vel_ned_callback, NULL, &vel_ned_node);
318  sbp_register_callback(&sbp_state, SBP_MSG_DOPS, &sbp_dops_callback, NULL, &dops_node);
319  sbp_register_callback(&sbp_state, SBP_MSG_GPS_TIME, &sbp_gps_time_callback, NULL, &gps_time_node);
320  sbp_register_callback(&sbp_state, SBP_MSG_TRACKING_STATE, &sbp_tracking_state_callback, NULL, &tracking_state_node);
321  sbp_register_callback(&sbp_state, SBP_MSG_TRACKING_STATE_DEP_A, &sbp_tracking_state_dep_a_callback, NULL, &tracking_state_dep_a_node);
322  sbp_register_callback(&sbp_state, SBP_MSG_HEARTBEAT, &spb_heartbeat_callback, NULL, &heartbeat_node);
323 
324  /* Write settings */
325  sbp_send_message(&sbp_state, SBP_MSG_SETTINGS_WRITE, SBP_SENDER_ID, sizeof(SBP_ANT_SET), (u8*)(&SBP_ANT_SET), gps_piksi_write);
326  sbp_send_message(&sbp_state, SBP_MSG_SETTINGS_WRITE, SBP_SENDER_ID, sizeof(SBP_UART_SET1), (u8*)(&SBP_UART_SET1), gps_piksi_write);
327  sbp_send_message(&sbp_state, SBP_MSG_SETTINGS_WRITE, SBP_SENDER_ID, sizeof(SBP_UART_SET2), (u8*)(&SBP_UART_SET2), gps_piksi_write);
328  sbp_send_message(&sbp_state, SBP_MSG_SETTINGS_WRITE, SBP_SENDER_ID, sizeof(SBP_UART_SET3), (u8*)(&SBP_UART_SET3), gps_piksi_write);
329  sbp_send_message(&sbp_state, SBP_MSG_SETTINGS_SAVE, SBP_SENDER_ID, 0, NULL, gps_piksi_write);
330  /*msg_base_pos_t base_pos;
331  base_pos.lat = 51.991152;
332  base_pos.lon = 4.378052;
333  base_pos.height = 50.;
334  sbp_send_message(&sbp_state, SBP_MSG_BASE_POS, SBP_SENDER_ID, sizeof(msg_base_pos_t), (u8*)(&base_pos), gps_piksi_write);*/
335 
336  // gps.nb_channels = GPS_NB_CHANNELS;
338 
339  gps_piksi.nb_channels = 10;
340 
341 #if PERIODIC_TELEMETRY
343 #endif
344 }
345 
346 /*
347  * Event handler for reading the GPS UART bytes
348  */
349 void gps_piksi_event(void)
350 {
351  if ( get_sys_time_msec() - time_since_last_pos_update > POS_ECEF_TIMEOUT ) {
353  }
354  // call sbp event function
355  if (uart_char_available(&(PIKSI_GPS_LINK)))
356  sbp_process(&sbp_state, &gps_piksi_read);
357 }
358 
359 /*
360  * Publish the GPS data from the Piksi on the ABI bus
361  */
362 static void gps_piksi_publish(void)
363 {
364  // current timestamp
365  uint32_t now_ts = get_sys_time_usec();
366 
369  if (gps_piksi.fix >= GPS_FIX_3D) {
372  }
373  AbiSendMsgGPS(GPS_PIKSI_ID, now_ts, &gps_piksi);
374 }
375 
376 /*
377  * Read bytes from the Piksi UART connection
378  * This is a wrapper functions used in the libsbp library
379  */
380 uint32_t gps_piksi_read(uint8_t *buff, uint32_t n, void *context __attribute__((unused)))
381 {
382  uint32_t i;
383  for (i = 0; i < n; i++) {
384  if (!uart_char_available(&(PIKSI_GPS_LINK)))
385  break;
386 
387  buff[i] = uart_getch(&(PIKSI_GPS_LINK));
388  }
389  return i;
390 }
391 
392 /*
393  * Write bytes to the Piksi UART connection
394  * This is a wrapper functions used in the libsbp library
395  */
396 uint32_t gps_piksi_write(uint8_t *buff, uint32_t n, void *context __attribute__((unused)))
397 {
398  uint32_t i = 0;
399  for (i = 0; i < n; i++) {
400  uart_put_byte(&(PIKSI_GPS_LINK), 0, buff[i]);
401  }
402  return n;
403 }
404 
408 void gps_inject_data(uint8_t packet_id, uint8_t length, uint8_t *data)
409 {
410  sbp_send_message(&sbp_state, packet_id, SBP_SENDER_ID, length, data, gps_piksi_write);
411 }
unsigned short uint16_t
Definition: types.h:16
int32_t z
in centimeters
static uint8_t get_fix_mode(uint8_t flags)
Definition: gps_piksi.c:283
#define GPS_PIKSI_ID
uint32_t gps_piksi_read(uint8_t *buff, uint32_t n, void *context)
Definition: gps_piksi.c:380
sbp_state_t sbp_state
Definition: gps_piksi.c:103
arch independent UART (Universal Asynchronous Receiver/Transmitter) API
struct SVinfo svinfos[GPS_NB_CHANNELS]
holds information from the Space Vehicles (Satellites)
Definition: gps.h:104
#define SBP_FIX_MODE_SPP
Definition: gps_piksi.c:50
uint32_t gps_piksi_write(uint8_t *buff, uint32_t n, void *context)
Definition: gps_piksi.c:396
sbp_msg_callbacks_node_t vel_ecef_node
Definition: gps_piksi.c:110
sbp_msg_callbacks_node_t tracking_state_dep_a_node
Definition: gps_piksi.c:116
uint32_t pacc
position accuracy in cm
Definition: gps.h:94
sbp_msg_callbacks_node_t heartbeat_node
Definition: gps_piksi.c:117
sbp_msg_callbacks_node_t gps_time_node
Definition: gps_piksi.c:114
static void sbp_tracking_state_dep_a_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:256
uint8_t nb_channels
Number of scanned satellites.
Definition: gps.h:103
#define GPS_VALID_VEL_NED_BIT
Definition: gps.h:52
Periodic telemetry system header (includes downlink utility and generated code).
uint8_t uart_getch(struct uart_periph *p)
Definition: uart_arch.c:822
uint32_t get_sys_time_msec(void)
Definition: sys_time_arch.c:78
uint8_t valid_fields
bitfield indicating valid fields (GPS_VALID_x_BIT)
Definition: gps.h:82
int32_t y
in centimeters
uint16_t week
GPS week.
Definition: gps.h:100
uint16_t uart_char_available(struct uart_periph *p)
Check UART for available chars in receive buffer.
Definition: uart_arch.c:296
Main include for ABI (AirBorneInterface).
static const char SBP_ANT_SET[]
Definition: gps_piksi.c:83
static void sbp_pos_llh_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:173
void gps_piksi_init(void)
Definition: gps_piksi.c:308
sbp_msg_callbacks_node_t dops_node
Definition: gps_piksi.c:113
uint8_t svid
Satellite ID.
Definition: gps.h:72
#define GPS_FIX_3D
3D GPS fix
Definition: gps.h:39
sbp_msg_callbacks_node_t pos_llh_node
Definition: gps_piksi.c:111
int32_t z
Down.
void gps_piksi_event(void)
Definition: gps_piksi.c:349
uint32_t last_3dfix_ticks
cpu time ticks at last valid 3D fix
Definition: gps.h:106
int32_t alt
in millimeters above WGS84 reference ellipsoid
uint32_t sacc
speed accuracy in cm/s
Definition: gps.h:95
static void gps_piksi_publish(void)
Definition: gps_piksi.c:362
int32_t y
East.
#define SPB_FIX_MODE_FIXED
Definition: gps_piksi.c:52
Paparazzi double-precision floating point math for geodetic calculations.
uint32_t last_msg_time
cpu time in sec at last received GPS message
Definition: gps.h:109
#define GPS_VALID_COURSE_BIT
Definition: gps.h:54
#define GPS_FIX_DGPS
DGPS fix.
Definition: gps.h:40
static void sbp_tracking_state_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:240
static void sbp_dops_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:221
struct GpsState gps_piksi
Definition: gps_piksi.c:59
int32_t hmsl
height above mean sea level (MSL) in mm
Definition: gps.h:88
uint8_t cno
Carrier to Noise Ratio (Signal Strength) in dbHz.
Definition: gps.h:75
static void send_piksi_heartbeat(struct transport_tx *trans, struct link_device *dev)
Definition: gps_piksi.c:67
struct GpsTimeSync gps_piksi_time_sync
Definition: gps_piksi.c:60
sbp_msg_callbacks_node_t pos_ecef_node
Definition: gps_piksi.c:109
data structure for GPS information
Definition: gps.h:81
uint32_t tow
GPS time of week in ms.
Definition: gps.h:101
#define GPS_FIX_NONE
No GPS fix.
Definition: gps.h:37
Device independent GPS code (interface)
uint16_t pdop
position dilution of precision scaled by 100
Definition: gps.h:97
int32_t x
North.
unsigned long uint32_t
Definition: types.h:18
static const char SBP_UART_SET3[]
Definition: gps_piksi.c:96
struct EcefCoor_i ecef_pos
position in ECEF in cm
Definition: gps.h:85
static uint32_t time_since_last_heartbeat
Definition: gps_piksi.c:62
#define GPS_VALID_HMSL_BIT
Definition: gps.h:53
uint32_t int32_sqrt(uint32_t in)
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
int32_t lon
in degrees*1e7
Driver for Piksi modules from Swift-Nav.
sbp_msg_callbacks_node_t tracking_state_node
Definition: gps_piksi.c:115
volatile uint32_t nb_sec_rem
remainder of seconds since startup in CPU_TICKS
Definition: sys_time.h:73
static void sbp_vel_ecef_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:157
signed long int32_t
Definition: types.h:19
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:73
void uart_put_byte(struct uart_periph *p, long fd, uint8_t data)
Uart transmit implementation.
Definition: uart_arch.c:917
#define GPS_FIX_RTK
RTK GPS fix.
Definition: gps.h:41
static const char SBP_UART_SET1[]
Definition: gps_piksi.c:94
uint32_t last_3dfix_time
cpu time in sec at last valid 3D fix
Definition: gps.h:107
static void sbp_pos_ecef_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:131
unsigned char uint8_t
Definition: types.h:14
int32_t course
GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
Definition: gps.h:93
uint8_t comp_id
id of current gps
Definition: gps.h:83
static const char SBP_UART_SET2[]
Definition: gps_piksi.c:95
volatile uint32_t nb_sec
full seconds since startup
Definition: sys_time.h:72
static uint32_t time_since_last_pos_update
Definition: gps_piksi.c:124
#define GPS_VALID_POS_ECEF_BIT
Definition: gps.h:48
static void sbp_gps_time_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:230
uint32_t last_msg_ticks
cpu time ticks at last received GPS message
Definition: gps.h:108
#define GPS_VALID_POS_LLA_BIT
Definition: gps.h:49
uint8_t num_sv
number of sat in fix
Definition: gps.h:98
int32_t x
in centimeters
uint16_t gspeed
norm of 2d ground speed in cm/s
Definition: gps.h:91
struct EcefCoor_i ecef_vel
speed ECEF in cm/s
Definition: gps.h:89
data structure for GPS time sync
Definition: gps.h:114
#define GPS_VALID_VEL_ECEF_BIT
Definition: gps.h:51
void gps_inject_data(uint8_t packet_id, uint8_t length, uint8_t *data)
Override the default GPS packet injector to inject the data trough UART.
Definition: gps_piksi.c:408
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
Definition: gps.h:86
static void spb_heartbeat_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:272
#define POS_ECEF_TIMEOUT
Definition: gps_piksi.c:54
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
Definition: sys_time_arch.c:68
int32_t lat
in degrees*1e7
uint8_t fix
status of fix
Definition: gps.h:99
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
struct NedCoor_i ned_vel
speed NED in cm/s
Definition: gps.h:90
struct GpsState gps
global GPS state
Definition: gps.c:75
static void sbp_vel_ned_callback(uint16_t sender_id, uint8_t len, uint8_t msg[], void *context)
Definition: gps_piksi.c:205
uint8_t buff[25]
Buffer used for general comunication over SPI (in buffer)
sbp_msg_callbacks_node_t vel_ned_node
Definition: gps_piksi.c:112
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:46
#define SBP_FIX_MODE_FLOAT
Definition: gps_piksi.c:51