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.c
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
32#include "modules/core/abi.h"
33
34// State interface for rotation compensation
35#include "state.h"
36
37// Messages
38#include "mcu_periph/uart.h"
39#include "pprzlink/messages.h"
41
45
46// message ID in Mavlink (v1.0)
47#define MAVLINK_OPTICAL_HEARTBEAT_MSG_ID 0
48#define MAVLINK_OPTICAL_FLOW_MSG_ID 100
49#define MAVLINK_OPTICAL_FLOW_RAD_MSG_ID 106
50
51/*
52 * acceptable quality of optical flow (0-min,1-max)
53 * higher threshold means fewer measurements will be available
54 * but they will be more precise. Generally it is probably a better
55 * idea to have lower threshold, and propagate the noise (1-quality)
56 * to the INS
57 */
58#ifndef PX4FLOW_QUALITY_THRESHOLD
59#define PX4FLOW_QUALITY_THRESHOLD 0.1
60#endif
61
62// request structs for mavlink decoder
66
67// enable/disable AGL updates
69
70// compensate AGL for body rotation
72
73// standard deviation of the measurement
75
76
77// callback function on message reception
79{
80 static float quality = 0;
81 static float noise = 0;
83 quality = ((float)optical_flow.quality) / 255.0;
84 noise = px4flow_stddev + (1 - quality) * px4flow_stddev * 10;
85 noise = noise * noise; // square the noise to get variance of the measurement
86
87 if (quality > PX4FLOW_QUALITY_THRESHOLD) {
88 // flip the axis (if the PX4FLOW is mounted as shown in
89 // https://pixhawk.org/modules/px4flow
94 0.0f,
95 noise,
96 noise,
97 -1.f);
98 }
99
100 // compensate AGL measurement for body rotation
102 float phi = stateGetNedToBodyEulers_f()->phi;
103 float theta = stateGetNedToBodyEulers_f()->theta;
104 float gain = (float)fabs( (double) (cosf(phi) * cosf(theta)));
107 }
108
109 if (px4flow_update_agl) {
110 // positive distance means it's known/valid
113 }
114 }
115}
116
124{
125 // TODO: do something useful with the data here
126}
127
129{
130 //TODO: Check whether we have a right version of firmware etc? i.e. heartbeat.autopilot=MAV_AUTOPILOT_PX4
131}
132
158
159
180
Main include for ABI (AirBorneInterface).
#define AGL_SONAR_PX4FLOW_ID
#define VEL_PX4FLOW_ID
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
float phi
in radians
float theta
in radians
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition state.h:1306
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
uint16_t foo
Definition main_demo5.c:58
static void decode_optical_flow_rad_msg(struct mavlink_message *msg)
According to https://pixhawk.org/modules/px4flow the PX4flow module outputs OPTICAL_FLOW_RAD message ...
Definition px4flow.c:123
struct mavlink_heartbeat heartbeat
Definition px4flow.c:42
#define MAVLINK_OPTICAL_FLOW_MSG_ID
Definition px4flow.c:48
#define PX4FLOW_QUALITY_THRESHOLD
Definition px4flow.c:59
static void decode_heartbeat_msg(struct mavlink_message *msg)
Definition px4flow.c:128
#define MAVLINK_OPTICAL_FLOW_RAD_MSG_ID
Definition px4flow.c:49
#define MAVLINK_OPTICAL_HEARTBEAT_MSG_ID
Definition px4flow.c:47
bool px4flow_compensate_rotation
Definition px4flow.c:71
bool px4flow_update_agl
Definition px4flow.c:68
struct mavlink_msg_req req_heartbeat
Definition px4flow.c:65
struct mavlink_optical_flow optical_flow
Definition px4flow.c:43
struct mavlink_msg_req req_flow
Definition px4flow.c:63
struct mavlink_msg_req req_flow_rad
Definition px4flow.c:64
static void decode_optical_flow_msg(struct mavlink_message *msg)
Definition px4flow.c:78
float px4flow_stddev
Definition px4flow.c:74
void px4flow_init(void)
Initialization function.
Definition px4flow.c:136
struct mavlink_optical_flow_rad optical_flow_rad
Definition px4flow.c:44
void px4flow_downlink(void)
Downlink message for debug.
Definition px4flow.c:163
driver for the optical flow sensor PX4FLOW
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
float flow_comp_m_x
Flow in meters in x-sensor direction, angular-speed compensated [meters/sec].
Definition px4flow.h:47
float flow_comp_m_y
Flow in meters in y-sensor direction, angular-speed compensated [meters/sec].
Definition px4flow.h:48
int32_t flow_x
Flow in pixels in x-sensor direction.
Definition px4flow.h:51
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
API to get/set the generic vehicle states.
arch independent UART (Universal Asynchronous Receiver/Transmitter) API
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.