Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
navdata.h
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 */
22 
33 #ifndef NAVDATA_H_
34 #define NAVDATA_H_
35 
36 #include "std.h"
37 #include <unistd.h>
38 
46 
50 
56 
58 
63 
67 
69 
70  uint32_t sum_echo; //unsigned long
72 
74 
77 
81 
83 
84 } __attribute__((packed));
85 
86 /* The baro calibration received from the navboard */
99 
100  // These values are calculated
102 };
103 
104 /* Navdata board defines */
105 #define NAVDATA_PACKET_SIZE 60
106 #define NAVDATA_START_BYTE 0x3A
107 #define NAVDATA_CMD_START 0x01
108 #define NAVDATA_CMD_STOP 0x02
109 #define NAVDATA_CMD_BARO_CALIB 0x17
110 
111 #define ARDRONE_GPIO_PORT 0x32524
112 #define ARDRONE_GPIO_PIN_NAVDATA 177
113 
114 /* Main navdata structure */
115 struct navdata_t {
117  int fd;
118 
124 
127 
130  bool imu_lost;
131 };
132 extern struct navdata_t navdata;
133 
134 
135 bool navdata_init(void);
136 void navdata_update(void);
137 int16_t navdata_height(void);
138 
139 /* FIXME: This should be moved to the uart handling part! */
140 ssize_t full_write(int fd, const uint8_t *buf, size_t count);
141 ssize_t full_read(int fd, uint8_t *buf, size_t count);
142 
143 #endif /* NAVDATA_H_ */
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
uint16_t
unsigned short uint16_t
Definition: types.h:16
navdata_update
void navdata_update(void)
Update the navdata (event loop)
Definition: navdata.c:343
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
bmp180_calib_t
Definition: navdata.h:87
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
navdata_measure_t::gradient
int16_t gradient
Definition: navdata.h:71
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
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
bmp180_calib_t::ac6
uint16_t ac6
Definition: navdata.h:93
uint32_t
unsigned long uint32_t
Definition: types.h:18
navdata_t::totalBytesRead
uint32_t totalBytesRead
Definition: navdata.h:119
navdata_measure_t::temperature_gyro
uint16_t temperature_gyro
Definition: navdata.h:55
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
navdata
struct navdata_t navdata
Definition: navdata.c:59
navdata_init
bool navdata_init(void)
Initialize the navdata board.
Definition: navdata.c:171
bmp180_calib_t::b2
int16_t b2
Definition: navdata.h:95
std.h
navdata_measure_t::my
int16_t my
Definition: navdata.h:78
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
bmp180_calib_t::mc
int16_t mc
Definition: navdata.h:97
navdata_measure_t::temperature_pressure
uint16_t temperature_pressure
Definition: navdata.h:76
int16_t
signed short int16_t
Definition: types.h:17
uint8_t
unsigned char uint8_t
Definition: types.h:14
navdata_measure_t::az
uint16_t az
Definition: navdata.h:49
bmp180_calib_t::b5
int32_t b5
Definition: navdata.h:101
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_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
navdata_measure_t::mz
int16_t mz
Definition: navdata.h:80
fd
int fd
Definition: serial.c:26
navdata_measure_t::us_association_echo
uint16_t us_association_echo
Definition: navdata.h:61
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
bmp180_calib_t::mb
int16_t mb
Definition: navdata.h:96
int32_t
signed long int32_t
Definition: types.h:19
bmp180_calib_t::ac5
uint16_t ac5
Definition: navdata.h:92
navdata_t::fd
int fd
The navdata file pointer.
Definition: navdata.h:117
bmp180_calib_t::ac1
int16_t ac1
Definition: navdata.h:88
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
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_t::packetsRead
uint32_t packetsRead
Definition: navdata.h:120
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
navdata_t::lost_imu_frames
uint32_t lost_imu_frames
Definition: navdata.h:122
navdata_t
Definition: navdata.h:115
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
navdata_measure_t::ax
uint16_t ax
Definition: navdata.h:47
navdata_measure_t::us_distance_echo
uint16_t us_distance_echo
Definition: navdata.h:62
navdata_height
int16_t navdata_height(void)