Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
navdata.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 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, see
18  * <http://www.gnu.org/licenses/>.
19  */
20 
21 /* Thanks to TU Delft by assigning students Dino Hensen, Vincent van Hoek for
22  * their inital work and later improvements made in 2015 by Freek van Tienen
23 */
24 
33 #include <stdio.h>
34 #include <stdlib.h>
35 #include <fcntl.h>
36 #include <termios.h> /* for baud rates and options */
37 #include <unistd.h>
38 #include <string.h>
39 #include <math.h>
40 #include <errno.h>
41 #include <assert.h>
42 #include <pthread.h>
43 
44 #include "std.h"
45 #include "navdata.h"
46 #include "subsystems/ins.h"
47 #include "subsystems/ahrs.h"
48 #include "subsystems/abi.h"
49 #include "mcu_periph/gpio.h"
50 
51 /* Internal used functions */
52 static void *navdata_read(void *data __attribute__((unused)));
53 static void navdata_cmd_send(uint8_t cmd);
54 static bool navdata_baro_calib(void);
55 static void mag_freeze_check(void);
56 static void baro_update_logic(void);
57 
58 /* Main navdata structure */
60 
64 static bool navdata_available = false;
65 
66 /* syncronization variables */
67 static pthread_mutex_t navdata_mutex = PTHREAD_MUTEX_INITIALIZER;
68 static pthread_cond_t navdata_cond = PTHREAD_COND_INITIALIZER;
69 
70 #ifndef NAVDATA_FILTER_ID
71 #define NAVDATA_FILTER_ID 2
72 #endif
73 
78 #ifndef SONAR_OFFSET
79 #define SONAR_OFFSET 880
80 #endif
81 
85 #ifndef SONAR_SCALE
86 #define SONAR_SCALE 0.00047
87 #endif
88 
92 ssize_t full_write(int fd, const uint8_t *buf, size_t count)
93 {
94  size_t written = 0;
95 
96  while (written < count) {
97  ssize_t n = write(fd, buf + written, count - written);
98  if (n < 0) {
99  if (errno == EAGAIN || errno == EWOULDBLOCK) {
100  continue;
101  }
102  return n;
103  }
104  written += n;
105  }
106  return written;
107 }
108 
112 ssize_t full_read(int fd, uint8_t *buf, size_t count)
113 {
114  /* Apologies for illiteracy, but we can't overload |read|.*/
115  size_t readed = 0;
116 
117  while (readed < count) {
118  ssize_t n = read(fd, buf + readed, count - readed);
119  if (n < 0) {
120  if (errno == EAGAIN || errno == EWOULDBLOCK) {
121  continue;
122  }
123  return n;
124  }
125  readed += n;
126  }
127  return readed;
128 }
129 
130 #if PERIODIC_TELEMETRY
132 
133 static void send_navdata(struct transport_tx *trans, struct link_device *dev)
134 {
135  pprz_msg_send_ARDRONE_NAVDATA(trans, dev, AC_ID,
138  &navdata.measure.ax,
139  &navdata.measure.ay,
140  &navdata.measure.az,
141  &navdata.measure.vx,
142  &navdata.measure.vy,
143  &navdata.measure.vz,
160  &navdata.measure.mx,
161  &navdata.measure.my,
162  &navdata.measure.mz,
165 }
166 #endif
167 
172 {
173  assert(sizeof(struct navdata_measure_t) == NAVDATA_PACKET_SIZE);
174 
175  /* Check if the FD isn't already initialized */
176  if (navdata.fd <= 0) {
177  navdata.fd = open("/dev/ttyO1", O_RDWR | O_NOCTTY); /* O_NONBLOCK doesn't work */
178 
179  if (navdata.fd < 0) {
180  printf("[navdata] Unable to open navdata board connection(/dev/ttyO1)\n");
181  return false;
182  }
183 
184  /* Update the settings of the UART connection */
185  fcntl(navdata.fd, F_SETFL, 0); /* read calls are non blocking */
186  /* set port options */
187  struct termios options;
188  /* Get the current options for the port */
189  tcgetattr(navdata.fd, &options);
190  /* Set the baud rates to 460800 */
191  cfsetispeed(&options, B460800);
192  cfsetospeed(&options, B460800);
193 
194  options.c_cflag |= (CLOCAL | CREAD); /* Enable the receiver and set local mode */
195  options.c_iflag = 0; /* clear input options */
196  options.c_lflag = 0; /* clear local options */
197  options.c_oflag &= ~OPOST; //clear output options (raw output)
198 
199  //Set the new options for the port
200  tcsetattr(navdata.fd, TCSANOW, &options);
201  }
202 
203  // Reset available flags
204  navdata_available = false;
205  navdata.baro_calibrated = false;
206  navdata.baro_available = false;
207  navdata.imu_lost = false;
208 
209  // Set all statistics to 0
213  navdata.packetsRead = 0;
215 
216  /* Stop acquisition */
218 
219  /* Read the baro calibration(blocking) */
220  if (!navdata_baro_calib()) {
221  printf("[navdata] Could not acquire baro calibration!\n");
222  return false;
223  }
224  navdata.baro_calibrated = true;
225 
226  /* Start acquisition */
228 
229  /* Set navboard gpio control */
232 
233  /* Start navdata reading thread */
234  pthread_t navdata_thread;
235  if (pthread_create(&navdata_thread, NULL, navdata_read, NULL) != 0) {
236  printf("[navdata] Could not create navdata reading thread!\n");
237  return false;
238  }
239  pthread_setname_np(navdata_thread, "pprz_navdata_thread");
240 
241 #if PERIODIC_TELEMETRY
242  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_ARDRONE_NAVDATA, send_navdata);
243 #endif
244 
245  /* Set to initialized */
246  navdata.is_initialized = true;
247  return true;
248 }
249 
250 
255 static void *navdata_read(void *data __attribute__((unused)))
256 {
257  /* Buffer insert index for reading/writing */
258  static uint8_t buffer_idx = 0;
259 
260  while (TRUE) {
261 
262  /* Wait until we are notified to read next data,
263  i.e. buffer has been copied in navdata_update */
264  pthread_mutex_lock(&navdata_mutex);
265  while (navdata_available) {
266  pthread_cond_wait(&navdata_cond, &navdata_mutex);
267  }
268  pthread_mutex_unlock(&navdata_mutex);
269 
270  /* Read new bytes */
271  int newbytes = read(navdata.fd, navdata_buffer + buffer_idx, NAVDATA_PACKET_SIZE - buffer_idx);
272 
273  /* When there was no signal interrupt */
274  if (newbytes > 0) {
275  buffer_idx += newbytes;
276  navdata.totalBytesRead += newbytes;
277  }
278 
279  /* If we got a full packet */
280  if (buffer_idx >= NAVDATA_PACKET_SIZE) {
281  /* check if the start byte is correct */
283  uint8_t *pint = memchr(navdata_buffer, NAVDATA_START_BYTE, buffer_idx);
284 
285  /* Check if we found the start byte in the read data */
286  if (pint != NULL) {
287  memmove(navdata_buffer, pint, NAVDATA_PACKET_SIZE - (pint - navdata_buffer));
288  buffer_idx = pint - navdata_buffer;
289  fprintf(stderr, "[navdata] sync error, startbyte not found, resetting...\n");
290  } else {
291  buffer_idx = 0;
292  }
293  continue;
294  }
295 
296  /* full packet read with startbyte at the beginning, reset insert index */
297  buffer_idx = 0;
298 
299  /* Calculate the checksum */
300  uint16_t checksum = 0;
301  for (int i = 2; i < NAVDATA_PACKET_SIZE - 2; i += 2) {
302  checksum += navdata_buffer[i] + (navdata_buffer[i + 1] << 8);
303  }
304 
305  struct navdata_measure_t *new_measurement = (struct navdata_measure_t *)navdata_buffer;
306 
307  /* Check if the checksum is OK */
308  if (new_measurement->chksum != checksum) {
309  fprintf(stderr, "[navdata] Checksum error [calculated: %d] [packet: %d] [diff: %d]\n",
310  checksum, new_measurement->chksum, checksum - new_measurement->chksum);
312  continue;
313  }
314 
315  /* Set flag that we have new valid navdata */
316  pthread_mutex_lock(&navdata_mutex);
317  navdata_available = true;
318  pthread_mutex_unlock(&navdata_mutex);
319  }
320  }
321 
322  return NULL;
323 }
324 
325 #include "subsystems/imu.h"
326 static void navdata_publish_imu(void)
327 {
333  imu_scale_mag(&imu);
334  uint32_t now_ts = get_sys_time_usec();
335  AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro);
336  AbiSendMsgIMU_ACCEL_INT32(IMU_BOARD_ID, now_ts, &imu.accel);
337  AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag);
338 }
339 
344 {
345  /* Check if initialized */
346  if (!navdata.is_initialized) {
347  navdata_init();
349  return;
350  }
351 
352  pthread_mutex_lock(&navdata_mutex);
353  /* If we got a new navdata packet */
354  if (navdata_available) {
355 
356  /* Copy the navdata packet */
358 
359  /* reset the flag */
360  navdata_available = false;
361  /* signal that we copied the buffer and new packet can be read */
362  pthread_cond_signal(&navdata_cond);
363  pthread_mutex_unlock(&navdata_mutex);
364 
365  /* Check if we missed a packet (our counter and the one from the navdata) */
368  fprintf(stderr, "[navdata] Lost frame: %d should have been %d\n",
371  }
373 
374  /* Invert byte order so that TELEMETRY works better */
375  uint8_t tmp;
377  tmp = p[0];
378  p[0] = p[1];
379  p[1] = tmp;
381  tmp = p[0];
382  p[0] = p[1];
383  p[1] = tmp;
384 
387 
388 #ifdef USE_SONAR
389  /* Check if there is a new sonar measurement and update the sonar */
390  if (navdata.measure.ultrasound >> 15) {
391  uint32_t now_ts = get_sys_time_usec();
392  float sonar_meas = (float)((navdata.measure.ultrasound & 0x7FFF) - SONAR_OFFSET) * SONAR_SCALE;
393  AbiSendMsgAGL(AGL_SONAR_ARDRONE2_ID, now_ts, sonar_meas);
394  }
395 #endif
396 
398 
400  } else {
401  /* no new packet available, still unlock mutex again */
402  pthread_mutex_unlock(&navdata_mutex);
403  }
404 }
405 
409 static void navdata_cmd_send(uint8_t cmd)
410 {
411  full_write(navdata.fd, &cmd, 1);
412 }
413 
414 
418 static bool navdata_baro_calib(void)
419 {
420  /* Start baro calibration acquisition */
422 
423  /* Receive the calibration (blocking) */
424  uint8_t calibBuffer[22];
425  if (full_read(navdata.fd, calibBuffer, sizeof calibBuffer) < 0) {
426  printf("[navdata] Could not read calibration data.");
427  return false;
428  }
429 
430  /* Convert the read bytes */
431  navdata.bmp180_calib.ac1 = calibBuffer[0] << 8 | calibBuffer[1];
432  navdata.bmp180_calib.ac2 = calibBuffer[2] << 8 | calibBuffer[3];
433  navdata.bmp180_calib.ac3 = calibBuffer[4] << 8 | calibBuffer[5];
434  navdata.bmp180_calib.ac4 = calibBuffer[6] << 8 | calibBuffer[7];
435  navdata.bmp180_calib.ac5 = calibBuffer[8] << 8 | calibBuffer[9];
436  navdata.bmp180_calib.ac6 = calibBuffer[10] << 8 | calibBuffer[11];
437  navdata.bmp180_calib.b1 = calibBuffer[12] << 8 | calibBuffer[13];
438  navdata.bmp180_calib.b2 = calibBuffer[14] << 8 | calibBuffer[15];
439  navdata.bmp180_calib.mb = calibBuffer[16] << 8 | calibBuffer[17];
440  navdata.bmp180_calib.mc = calibBuffer[18] << 8 | calibBuffer[19];
441  navdata.bmp180_calib.md = calibBuffer[20] << 8 | calibBuffer[21];
442 
443  return true;
444 }
445 
450 static void mag_freeze_check(void)
451 {
452  /* Thanks to Daren.G.Lee for initial fix on 20140530 */
453  static int16_t LastMagValue = 0;
454  static int MagFreezeCounter = 0;
455 
456  if (LastMagValue == navdata.measure.mx) {
457  MagFreezeCounter++;
458 
459  /* Has to have at least 30 times the exact same value to consider it a frozen magnetometer value */
460  if (MagFreezeCounter > 30) {
461  fprintf(stderr, "mag freeze detected, resetting!\n");
462 
463  /* set imu_lost flag */
464  navdata.imu_lost = true;
466 
467  /* Stop acquisition */
469 
470  /* Reset the hardware of the navboard */
472  usleep(20000);
474 
475  /* Wait for 40ms for it to boot */
476  usleep(40000);
477 
478  /* Start the navdata again and reset the counter */
480  MagFreezeCounter = 0; /* reset counter back to zero */
481  }
482  } else {
483  navdata.imu_lost = false;
484  /* Reset counter if value _does_ change */
485  MagFreezeCounter = 0;
486  }
487  /* set last value */
488  LastMagValue = navdata.measure.mx;
489 }
490 
496 static void baro_update_logic(void)
497 {
498  static int32_t lastpressval = 0;
499  static uint16_t lasttempval = 0;
500  static int32_t lastpressval_nospike = 0;
501  static uint16_t lasttempval_nospike = 0;
502  static uint8_t temp_or_press_was_updated_last =
503  0; /* 0 = press, so we now wait for temp, 1 = temp so we now wait for press */
504 
505  static int sync_errors = 0;
506  static int spike_detected = 0;
507 
508  if (temp_or_press_was_updated_last == 0) { /* Last update was press so we are now waiting for temp */
509  /* temp was updated */
510  temp_or_press_was_updated_last = true;
511 
512  /* This means that press must remain constant */
513  if (lastpressval != 0) {
514  /* If pressure was updated: this is a sync error */
515  if (lastpressval != navdata.measure.pressure) {
516  /* wait for temp again */
517  temp_or_press_was_updated_last = false;
518  sync_errors++;
519  //printf("Baro-Logic-Error (expected updated temp, got press)\n");
520  }
521  }
522  } else {
523  /* press was updated */
524  temp_or_press_was_updated_last = false;
525 
526  /* This means that temp must remain constant */
527  if (lasttempval != 0) {
528  /* If temp was updated: this is a sync error */
529  if (lasttempval != navdata.measure.temperature_pressure) {
530  /* wait for press again */
531  temp_or_press_was_updated_last = true;
532  sync_errors++;
533  //printf("Baro-Logic-Error (expected updated press, got temp)\n");
534 
535  } else {
536  /* We now got valid pressure and temperature */
537  navdata.baro_available = true;
538  }
539  }
540  }
541 
542  /* Detected a pressure swap */
543  if (lastpressval != 0 && lasttempval != 0
544  && ABS(lastpressval - navdata.measure.pressure) > ABS(lasttempval - navdata.measure.pressure)) {
545  navdata.baro_available = false;
546  }
547 
548  /* Detected a temprature swap */
549  if (lastpressval != 0 && lasttempval != 0
550  && ABS(lasttempval - navdata.measure.temperature_pressure) > ABS(lastpressval - navdata.measure.temperature_pressure)) {
551  navdata.baro_available = false;
552  }
553 
554  lasttempval = navdata.measure.temperature_pressure;
555  lastpressval = navdata.measure.pressure;
556 
557  /*
558  * It turns out that a lot of navdata boards have a problem (probably interrupt related)
559  * in which reading I2C data and writing uart output data is interrupted very long (50% of 200Hz).
560  * Afterwards, the 200Hz loop tries to catch up lost time but reads the baro too fast swapping the
561  * pressure and temperature values by exceeding the minimal conversion time of the bosh baro. The
562  * normal Parrot firmware seems to be perfectly capable to fly with this, either with excessive use of
563  * the sonar or with software filtering or spike detection. Paparazzi with its tightly coupled baro-altitude
564  * had problems. Since this problems looks not uncommon a detector was made. A lot of evidence is grabbed
565  * with a logic analyzer on the navboard I2C and serial output. The UART CRC is still perfect, the baro
566  * temp-press-temp-press logic is still perfect, so not easy to detect. Temp and pressure are swapped,
567  * and since both can have almost the same value, the size of the spike is not predictable. However at
568  * every spike of at least 3 broken boards the press and temp are byte-wise exactly the same due to
569  * reading them too quickly (trying to catch up for delay that happened earlier due to still non understood
570  * reasons. As pressure is more likely to quickly change, a small (yet unlikely) spike on temperature together with
571  * press==temp yields very good results as a detector, although theoretically not perfect.
572 
573  #samp press temp.
574  50925 39284 34501
575  50926 39287 34501
576  50927 39287 34501
577  50928 39283 34501 // *press good -> baro
578  50929 39283 34501
579  50930 39285 34501 // *press good -> baro
580  50931 39285 34500
581  50932 34500 34500 // press read too soon from chip (<4.5ms) -> ADC register still previous temp value
582  50933 34500 36618 // press not updated, still wrong. Temp is weird: looks like the average of both
583  50934 39284 36618 // new press read, but temp still outdated
584  50935 39284 34501
585  50936 39284 34501 // *press good -> baro
586  50937 39284 34500
587  50938 39281 34500
588  50939 39281 34500
589  50940 39280 34500
590  50941 39280 34502
591  50942 39280 34502
592  50943 39280 34501
593 
594  */
595 
596  /* If press and temp are same and temp has jump: neglect the next frame */
598  navdata.measure.pressure) { // && (abs((int32_t)navdata.temperature_pressure - (int32_t)lasttempval) > 40))
599  /* dont use the next 3 packets */
600  spike_detected = 3;
601  }
602 
603  if (spike_detected > 0) {
604  /* disable kalman filter use */
605  navdata.baro_available = false;
606 
607  // override both to last good
608  navdata.measure.pressure = lastpressval_nospike;
609  navdata.measure.temperature_pressure = lasttempval_nospike;
610 
611  /* Countdown */
612  spike_detected--;
613  } else { // both are good
614  lastpressval_nospike = navdata.measure.pressure;
615  lasttempval_nospike = navdata.measure.temperature_pressure;
616  }
617 }
navdata.h
Imu::gyro_unscaled
struct Int32Rates gyro_unscaled
unscaled gyroscope measurements
Definition: imu.h:46
navdata_measure_t::nb_echo
uint16_t nb_echo
Definition: navdata.h:68
navdata_measure_t::vz
int16_t vz
Definition: navdata.h:53
navdata_t::is_initialized
bool is_initialized
Check if the navdata board is initialized.
Definition: navdata.h:116
ins.h
uint16_t
unsigned short uint16_t
Definition: types.h:16
navdata_t::measure
struct navdata_measure_t measure
Main navdata packet receieved from navboard.
Definition: navdata.h:125
navdata_t::last_packet_number
uint16_t last_packet_number
Definition: navdata.h:123
navdata_read
static void * navdata_read(void *data)
Main reading thread This is done asynchronous because the navdata board doesn't support NON_BLOCKING.
Definition: navdata.c:255
navdata_measure_t::us_curve_ref
uint16_t us_curve_ref
Definition: navdata.h:66
navdata_measure_t::ultrasound
uint16_t ultrasound
Definition: navdata.h:57
SONAR_OFFSET
#define SONAR_OFFSET
Sonar offset.
Definition: navdata.c:79
abi.h
navdata_measure_t::gradient
int16_t gradient
Definition: navdata.h:71
Imu::accel
struct Int32Vect3 accel
accelerometer measurements in m/s^2 in BFP with INT32_ACCEL_FRAC
Definition: imu.h:39
baro_update_logic
static void baro_update_logic(void)
Handle the baro(pressure/temperature) logic Sometimes the temperature and pressure are switched becau...
Definition: navdata.c:496
navdata_measure_t::pressure
int32_t pressure
Definition: navdata.h:75
navdata_measure_t::flag_echo_ini
uint16_t flag_echo_ini
Definition: navdata.h:73
bmp180_calib_t::b1
int16_t b1
Definition: navdata.h:94
NAVDATA_START_BYTE
#define NAVDATA_START_BYTE
Definition: navdata.h:106
bmp180_calib_t::ac3
int16_t ac3
Definition: navdata.h:90
navdata_measure_t::us_debut_echo
uint16_t us_debut_echo
Definition: navdata.h:59
navdata_measure_t::chksum
uint16_t chksum
Definition: navdata.h:82
gpio_setup_output
void gpio_setup_output(ioportid_t port, uint16_t gpios)
Setup one or more pins of the given GPIO port as outputs.
Definition: gpio_arch.c:33
bmp180_calib_t::ac6
uint16_t ac6
Definition: navdata.h:93
uint32_t
unsigned long uint32_t
Definition: types.h:18
navdata_update
void navdata_update()
Update the navdata (event loop)
Definition: navdata.c:343
navdata_baro_calib
static bool navdata_baro_calib(void)
Try to receive the baro calibration from the navdata board.
Definition: navdata.c:418
navdata_t::totalBytesRead
uint32_t totalBytesRead
Definition: navdata.h:119
NAVDATA_CMD_BARO_CALIB
#define NAVDATA_CMD_BARO_CALIB
Definition: navdata.h:109
navdata_measure_t::temperature_gyro
uint16_t temperature_gyro
Definition: navdata.h:55
AGL_SONAR_ARDRONE2_ID
#define AGL_SONAR_ARDRONE2_ID
Definition: abi_sender_ids.h:133
IMU_BOARD_ID
#define IMU_BOARD_ID
Definition: abi_sender_ids.h:275
navdata_measure_t
Main navdata structure from the navdata board This is received from the navdata board at ~200Hz.
Definition: navdata.h:43
navdata_measure_t::temperature_acc
uint16_t temperature_acc
Definition: navdata.h:54
navdata_measure_t::us_fin_echo
uint16_t us_fin_echo
Definition: navdata.h:60
Imu::accel_unscaled
struct Int32Vect3 accel_unscaled
unscaled accelerometer measurements
Definition: imu.h:47
SONAR_SCALE
#define SONAR_SCALE
Sonar scale.
Definition: navdata.c:86
get_sys_time_usec
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
Definition: sys_time_arch.c:68
bmp180_calib_t::b2
int16_t b2
Definition: navdata.h:95
gpio_clear
static void gpio_clear(ioportid_t port, uint16_t pin)
Clear a gpio output to low level.
Definition: gpio_arch.h:108
telemetry.h
imu.h
full_read
ssize_t full_read(int fd, uint8_t *buf, size_t count)
Read from fd even while being interrupted.
Definition: navdata.c:112
RATES_ASSIGN
#define RATES_ASSIGN(_ra, _p, _q, _r)
Definition: pprz_algebra.h:330
std.h
navdata_measure_t::my
int16_t my
Definition: navdata.h:78
B460800
#define B460800
Definition: uart_arch.h:42
navdata_measure_t::sum_echo
uint32_t sum_echo
Definition: navdata.h:70
bmp180_calib_t::md
int16_t md
Definition: navdata.h:98
navdata_t::checksum_errors
uint32_t checksum_errors
Definition: navdata.h:121
navdata_measure_t::us_curve_value
uint16_t us_curve_value
Definition: navdata.h:65
navdata_publish_imu
static void navdata_publish_imu(void)
Definition: navdata.c:326
bmp180_calib_t::mc
int16_t mc
Definition: navdata.h:97
dev
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:74
navdata_measure_t::temperature_pressure
uint16_t temperature_pressure
Definition: navdata.h:76
send_navdata
static void send_navdata(struct transport_tx *trans, struct link_device *dev)
Definition: navdata.c:133
int16_t
signed short int16_t
Definition: types.h:17
imu_scale_gyro
void imu_scale_gyro(struct Imu *_imu)
Definition: imu_vectornav.c:43
uint8_t
unsigned char uint8_t
Definition: types.h:14
register_periodic_telemetry
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:46
navdata_measure_t::az
uint16_t az
Definition: navdata.h:49
navdata_measure_t::nu_trame
uint16_t nu_trame
Definition: navdata.h:45
navdata_measure_t::vx
int16_t vx
Definition: navdata.h:51
NAVDATA_PACKET_SIZE
#define NAVDATA_PACKET_SIZE
Definition: navdata.h:105
navdata_measure_t::vy
int16_t vy
Definition: navdata.h:52
bmp180_calib_t::ac4
uint16_t ac4
Definition: navdata.h:91
navdata_measure_t::taille
uint16_t taille
Definition: navdata.h:44
navdata_t::baro_calibrated
bool baro_calibrated
Whenever the baro is calibrated.
Definition: navdata.h:128
ahrs.h
imu
struct Imu imu
global IMU state
Definition: imu.c:108
ARDRONE_GPIO_PIN_NAVDATA
#define ARDRONE_GPIO_PIN_NAVDATA
Definition: navdata.h:112
navdata_measure_t::mz
int16_t mz
Definition: navdata.h:80
navdata_available
static bool navdata_available
flag to indicate new packet is available in buffer
Definition: navdata.c:64
navdata
struct navdata_t navdata
Definition: navdata.c:59
fd
int fd
Definition: serial.c:26
navdata_cmd_send
static void navdata_cmd_send(uint8_t cmd)
Sends a one byte command.
Definition: navdata.c:409
navdata_measure_t::us_association_echo
uint16_t us_association_echo
Definition: navdata.h:61
ARDRONE_GPIO_PORT
#define ARDRONE_GPIO_PORT
Definition: actuators.c:58
bmp180_calib_t::mb
int16_t mb
Definition: navdata.h:96
gpio.h
int32_t
signed long int32_t
Definition: types.h:19
bmp180_calib_t::ac5
uint16_t ac5
Definition: navdata.h:92
navdata_init
bool navdata_init()
Initialize the navdata board.
Definition: navdata.c:171
imu_scale_mag
void imu_scale_mag(struct Imu *_imu)
Definition: ahrs_gx3.c:352
navdata_t::fd
int fd
The navdata file pointer.
Definition: navdata.h:117
bmp180_calib_t::ac1
int16_t ac1
Definition: navdata.h:88
NAVDATA_CMD_STOP
#define NAVDATA_CMD_STOP
Definition: navdata.h:108
bmp180_calib_t::ac2
int16_t ac2
Definition: navdata.h:89
navdata_t::baro_available
bool baro_available
Whenever the baro is available.
Definition: navdata.h:129
navdata_measure_t::mx
int16_t mx
Definition: navdata.h:79
Imu::mag
struct Int32Vect3 mag
magnetometer measurements scaled to 1 in BFP with INT32_MAG_FRAC
Definition: imu.h:40
Imu::mag_unscaled
struct Int32Vect3 mag_unscaled
unscaled magnetometer measurements
Definition: imu.h:48
navdata_measure_t::ay
uint16_t ay
Definition: navdata.h:48
navdata_t::imu_lost
bool imu_lost
Whenever the imu is lost.
Definition: navdata.h:130
navdata_buffer
static uint8_t navdata_buffer[NAVDATA_PACKET_SIZE]
Buffer filled in the thread (maximum one navdata packet)
Definition: navdata.c:62
navdata_t::packetsRead
uint32_t packetsRead
Definition: navdata.h:120
VECT3_ASSIGN
#define VECT3_ASSIGN(_a, _x, _y, _z)
Definition: pprz_algebra.h:125
NAVDATA_CMD_START
#define NAVDATA_CMD_START
Definition: navdata.h:107
TRUE
#define TRUE
Definition: std.h:4
navdata_mutex
static pthread_mutex_t navdata_mutex
Definition: navdata.c:67
navdata_t::lost_imu_frames
uint32_t lost_imu_frames
Definition: navdata.h:122
navdata_t
Definition: navdata.h:115
checksum
static uint8_t checksum
Definition: airspeed_uADC.c:61
gpio_set
static void gpio_set(ioportid_t port, uint16_t pin)
Set a gpio output to high level.
Definition: gpio_arch.h:98
full_write
ssize_t full_write(int fd, const uint8_t *buf, size_t count)
Write to fd even while being interrupted.
Definition: navdata.c:92
mag_freeze_check
static void mag_freeze_check(void)
Check if the magneto is frozen Unknown why this bug happens.
Definition: navdata.c:450
navdata_measure_t::us_curve_time
uint16_t us_curve_time
Definition: navdata.h:64
navdata_t::bmp180_calib
struct bmp180_calib_t bmp180_calib
BMP180 calibration receieved from navboard.
Definition: navdata.h:126
imu_scale_accel
void imu_scale_accel(struct Imu *_imu)
Definition: imu_vectornav.c:44
DefaultPeriodic
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
navdata_measure_t::ax
uint16_t ax
Definition: navdata.h:47
p
static float p[2][2]
Definition: ins_alt_float.c:268
navdata_measure_t::us_distance_echo
uint16_t us_distance_echo
Definition: navdata.h:62
Imu::gyro
struct Int32Rates gyro
gyroscope measurements in rad/s in BFP with INT32_RATE_FRAC
Definition: imu.h:38
navdata_cond
static pthread_cond_t navdata_cond
Definition: navdata.c:68