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
px4flow_i2c.h
Go to the documentation of this file.
1/*
2 * Copyright (C) 2013 Gautier Hattenberger
3 * 2016 Michal Podhradsky <michal.podhradsky@aggiemail.usu.edu>
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
30#ifndef PX4FLOW_I2C_H
31#define PX4FLOW_I2C_H
32
33#include "std.h"
34#include "mcu_periph/i2c.h"
35
43
45{
46 uint16_t frame_count;// counts created I2C frames [#frames]
47 int16_t pixel_flow_x_sum;// latest x flow measurement in pixels*10 [pixels]
48 int16_t pixel_flow_y_sum;// latest y flow measurement in pixels*10 [pixels]
49 int16_t flow_comp_m_x;// x velocity*1000 [meters/sec]
50 int16_t flow_comp_m_y;// y velocity*1000 [meters/sec]
51 int16_t qual;// Optical flow quality / confidence [0: bad, 255: maximum quality]
52 int16_t gyro_x_rate; // latest gyro x rate [rad/sec]
53 int16_t gyro_y_rate; // latest gyro y rate [rad/sec]
54 int16_t gyro_z_rate; // latest gyro z rate [rad/sec]
55 uint8_t gyro_range; // gyro range [0 .. 7] equals [50 deg/sec .. 2000 deg/sec]
56 uint8_t sonar_timestamp;// time since last sonar update [milliseconds]
57 int16_t ground_distance;// Ground distance in meters*1000 [meters]. Positive value: distance known. Negative value: Unknown distance
58};
59
61{
62 uint16_t frame_count_since_last_readout;//number of flow measurements since last I2C readout [#frames]
63 int16_t pixel_flow_x_integral;//accumulated flow in radians*10000 around x axis since last I2C readout [rad*10000]
64 int16_t pixel_flow_y_integral;//accumulated flow in radians*10000 around y axis since last I2C readout [rad*10000]
65 int16_t gyro_x_rate_integral;//accumulated gyro x rates in radians*10000 since last I2C readout [rad*10000]
66 int16_t gyro_y_rate_integral;//accumulated gyro y rates in radians*10000 since last I2C readout [rad*10000]
67 int16_t gyro_z_rate_integral;//accumulated gyro z rates in radians*10000 since last I2C readout [rad*10000]
68 uint32_t integration_timespan;//accumulation timespan in microseconds since last I2C readout [microseconds]
69 uint32_t sonar_timestamp;// time since last sonar update [microseconds]
70 int16_t ground_distance;// Ground distance in meters*1000 [meters*1000]
71 int16_t gyro_temperature;// Temperature * 100 in centi-degrees Celsius [degcelsius*100]
72 uint8_t qual;// averaged quality of accumulated flow values [0:bad quality;255: max quality]
73};
74
86
87extern struct px4flow_data px4flow;
88
89extern void px4flow_i2c_init(void);
90extern void px4flow_i2c_periodic(void);
91extern void px4flow_i2c_downlink(void);
92
93
94#endif /* PX4FLOW_I2C_H */
95
I2C transaction structure.
Definition i2c.h:93
Architecture independent I2C (Inter-Integrated Circuit Bus) API.
uint16_t frame_count
Definition px4flow_i2c.h:46
bool compensate_rotation
Definition px4flow_i2c.h:84
int16_t pixel_flow_x_sum
Definition px4flow_i2c.h:47
int16_t flow_comp_m_y
Definition px4flow_i2c.h:50
void px4flow_i2c_periodic(void)
Poll px4flow for data 152 i2c frames are created per second, so the PX4FLOW can be polled at up to 15...
struct i2c_transaction trans
Definition px4flow_i2c.h:79
uint16_t frame_count_since_last_readout
Definition px4flow_i2c.h:62
int16_t ground_distance
Definition px4flow_i2c.h:57
int16_t pixel_flow_y_sum
Definition px4flow_i2c.h:48
enum Px4FlowStatus status
Definition px4flow_i2c.h:82
Px4FlowStatus
Definition px4flow_i2c.h:36
@ PX4FLOW_FRAME_REC
Definition px4flow_i2c.h:38
@ PX4FLOW_INT_FRAME_REC
Definition px4flow_i2c.h:40
@ PX4FLOW_INT_FRAME_REQ
Definition px4flow_i2c.h:39
@ PX4FLOW_FRAME_REQ
Definition px4flow_i2c.h:37
@ PX4FLOW_INT_FRAME_REC_OK
Definition px4flow_i2c.h:41
void px4flow_i2c_downlink(void)
Downlink message for debug Copy volatile variables from the px4_i2c_frame for safety.
void px4flow_i2c_init(void)
Initialization function.
uint8_t addr
Definition px4flow_i2c.h:80
struct px4flow_i2c_integral_frame i2c_int_frame
Definition px4flow_i2c.h:78
struct px4flow_i2c_frame i2c_frame
Definition px4flow_i2c.h:77
struct px4flow_data px4flow
Definition px4flow_i2c.c:52
int16_t flow_comp_m_x
Definition px4flow_i2c.h:49
uint8_t sonar_timestamp
Definition px4flow_i2c.h:56
unsigned short uint16_t
Typedef defining 16 bit unsigned short 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.