39 #include "pprzlink/messages.h"
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
58 #ifndef PX4FLOW_QUALITY_THRESHOLD
59 #define PX4FLOW_QUALITY_THRESHOLD 0.1
80 static float quality = 0;
81 static float noise = 0;
85 noise = noise * noise;
104 float gain = (float)fabs( (
double) (cosf(phi) * cosf(theta)));
165 static float timestamp = 0;
166 static uint8_t distance_quality = 0;
Main include for ABI (AirBorneInterface).
#define AGL_SONAR_PX4FLOW_ID
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
Common code for AP and FBW telemetry.
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
struct mavlink_transport mavlink_tp
simple decoder of mavlink message
static void mavlink_register_msg(struct mavlink_transport *t, struct mavlink_msg_req *req)
Register a callback for a mavlink message.
Mavlink v1.0 message structure.
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 ...
struct mavlink_heartbeat heartbeat
#define MAVLINK_OPTICAL_FLOW_MSG_ID
#define PX4FLOW_QUALITY_THRESHOLD
static void decode_heartbeat_msg(struct mavlink_message *msg)
#define MAVLINK_OPTICAL_FLOW_RAD_MSG_ID
#define MAVLINK_OPTICAL_HEARTBEAT_MSG_ID
bool px4flow_compensate_rotation
struct mavlink_msg_req req_heartbeat
struct mavlink_optical_flow optical_flow
struct mavlink_msg_req req_flow
struct mavlink_msg_req req_flow_rad
static void decode_optical_flow_msg(struct mavlink_message *msg)
void px4flow_init(void)
Initialization function.
struct mavlink_optical_flow_rad optical_flow_rad
void px4flow_downlink(void)
Downlink message for debug.
driver for the optical flow sensor PX4FLOW
float distance
Distance measured without compensation in meters.
uint8_t quality
Optical flow quality / confidence. 0: bad, 255: maximum quality.
float flow_comp_m_x
Flow in meters in x-sensor direction, angular-speed compensated [meters/sec].
float flow_comp_m_y
Flow in meters in y-sensor direction, angular-speed compensated [meters/sec].
int32_t flow_x
Flow in pixels in x-sensor direction.
uint64_t time_usec
Timestamp (UNIX)
float ground_distance
Ground distance in meters. Positive value: distance known. Negative value: Unknown distance.
int32_t flow_y
Flow in pixels in y-sensor direction.
uint8_t sensor_id
Sensor ID.
Mavlink optical flow structure.
Mavlink optical flow rad structure.
API to get/set the generic vehicle states.
Structure to submit a callback.
void(* callback)(struct mavlink_message *msg)
Callback function.
struct mavlink_message msg
Mavlink message.
uint8_t msg_id
Requested message ID.
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.