Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
px4flow.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_H
31 #define PX4FLOW_H
32 
33 #include "std.h"
34 
35 // control variables
36 extern bool px4flow_update_agl;
37 extern bool px4flow_compensate_rotation;
38 extern float px4flow_stddev;
39 
47  float flow_comp_m_x;
48  float flow_comp_m_y;
50  float distance;
55 };
56 
63  // Timestamp (microseconds, synced to UNIX time or since system boot)
65  // Sensor ID
67  // Integration time in microseconds.
68  // Divide integrated_x and integrated_y by the integration time to obtain average flow.
70  // Flow in radians around X axis
71  // Sensor RH rotation about the X axis induces a positive flow.
72  // Sensor linear motion along the positive Y axis induces a negative flow.
73  float integrated_x;
74  // Flow in radians around Y axis
75  // Sensor RH rotation about the Y axis induces a positive flow.
76  // Sensor linear motion along the positive X axis induces a positive flow.
77  float integrated_y;
78  // RH rotation around X axis (rad)
80  // RH rotation around Y axis (rad)
82  // RH rotation around Z axis (rad)
84  // Temperature * 100 in centi-degrees Celsius
86  // Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
88  // Time in microseconds since the distance was sampled.
90  // Distance to the center of the flow field in meters.
91  // Positive value (including zero): distance known.
92  // Negative value: Unknown distance.
93  float distance;
94 };
95 
97  uint8_t type; // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
98  uint8_t autopilot; // Autopilot type / class. defined in MAV_AUTOPILOT ENUM
99  uint8_t base_mode; // System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
100  uint32_t custom_mode; // A bitfield for use for autopilot-specific flags.
101  uint8_t system_status; // System status flag, see MAV_STATE ENUM
102  uint8_t mavlink_version; //_mavlink_version MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
103 };
104 
105 
106 extern struct mavlink_heartbeat heartbeat;
107 extern struct mavlink_optical_flow optical_flow;
109 
110 extern void px4flow_init(void);
111 extern void px4flow_downlink(void);
112 
113 #endif /* PX4FLOW_H */
114 
struct mavlink_heartbeat heartbeat
Definition: px4flow.c:42
uint8_t type
Definition: px4flow.h:97
float distance
Distance measured without compensation in meters.
Definition: px4flow.h:50
uint8_t quality
Optical flow quality / confidence. 0: bad, 255: maximum quality.
Definition: px4flow.h:54
uint32_t custom_mode
Definition: px4flow.h:100
bool px4flow_compensate_rotation
Definition: px4flow.c:71
bool px4flow_update_agl
Definition: px4flow.c:68
uint8_t autopilot
Definition: px4flow.h:98
uint32_t integration_time_us
Definition: px4flow.h:69
uint8_t system_status
Definition: px4flow.h:101
struct mavlink_optical_flow optical_flow
Definition: px4flow.c:43
float flow_comp_m_x
Flow in meters in x-sensor direction, angular-speed compensated [meters/sec].
Definition: px4flow.h:47
uint32_t time_delta_distance_us
Definition: px4flow.h:89
float flow_comp_m_y
Flow in meters in y-sensor direction, angular-speed compensated [meters/sec].
Definition: px4flow.h:48
float px4flow_stddev
Definition: px4flow.c:74
uint8_t mavlink_version
Definition: px4flow.h:102
int32_t flow_x
Flow in pixels in x-sensor direction.
Definition: px4flow.h:51
void px4flow_init(void)
Initialization function.
Definition: px4flow.c:136
uint64_t time_usec
Timestamp (UNIX)
Definition: px4flow.h:46
float ground_distance
Ground distance in meters. Positive value: distance known. Negative value: Unknown distance.
Definition: px4flow.h:49
int32_t flow_y
Flow in pixels in y-sensor direction.
Definition: px4flow.h:52
uint8_t sensor_id
Sensor ID.
Definition: px4flow.h:53
struct mavlink_optical_flow_rad optical_flow_rad
Definition: px4flow.c:44
uint8_t base_mode
Definition: px4flow.h:99
void px4flow_downlink(void)
Downlink message for debug.
Definition: px4flow.c:163
int int32_t
Typedef defining 32 bit int type.
Definition: vl53l1_types.h:83
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
Definition: vl53l1_types.h:78
short int16_t
Typedef defining 16 bit short type.
Definition: vl53l1_types.h:93
unsigned long long uint64_t
Definition: vl53l1_types.h:72
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
Definition: vl53l1_types.h:98