Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
driver for the optical flow sensor PX4FLOW More...
#include "std.h"
Go to the source code of this file.
Data Structures | |
struct | mavlink_optical_flow |
Mavlink optical flow structure. More... | |
struct | mavlink_optical_flow_rad |
Mavlink optical flow rad structure. More... | |
struct | mavlink_heartbeat |
Functions | |
void | px4flow_init (void) |
Initialization function. More... | |
void | px4flow_downlink (void) |
Downlink message for debug. More... | |
Variables | |
bool | px4flow_update_agl |
bool | px4flow_compensate_rotation |
float | px4flow_stddev |
struct mavlink_heartbeat | heartbeat |
struct mavlink_optical_flow | optical_flow |
struct mavlink_optical_flow_rad | optical_flow_rad |
driver for the optical flow sensor PX4FLOW
Sensor from the PIXHAWK project
Definition in file px4flow.h.
struct mavlink_optical_flow |
Mavlink optical flow structure.
Using MAVLINK v1.0 generated code: Message ID 100 Fields are ordered to guarantee alignment
Data Fields | ||
---|---|---|
float | distance | Distance measured without compensation in meters. |
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. |
int32_t | flow_y | Flow in pixels in y-sensor direction. |
float | ground_distance | Ground distance in meters. Positive value: distance known. Negative value: Unknown distance. |
uint8_t | quality | Optical flow quality / confidence. 0: bad, 255: maximum quality. |
uint8_t | sensor_id | Sensor ID. |
uint64_t | time_usec | Timestamp (UNIX) |
struct mavlink_optical_flow_rad |
Mavlink optical flow rad structure.
Using MAVLINK v1.0 generated code: Message ID 106 Fields are ordered to guarantee alignment
Data Fields | ||
---|---|---|
float | distance | |
float | integrated_x | |
float | integrated_xgyro | |
float | integrated_y | |
float | integrated_ygyro | |
float | integrated_zgyro | |
uint32_t | integration_time_us | |
uint8_t | quality | |
uint8_t | sensor_id | |
int16_t | temperature | |
uint32_t | time_delta_distance_us | |
uint64_t | time_usec |
struct mavlink_heartbeat |
void px4flow_downlink | ( | void | ) |
Downlink message for debug.
Definition at line 163 of file px4flow.c.
References DefaultChannel, DefaultDevice, mavlink_optical_flow::distance, mavlink_optical_flow::flow_comp_m_x, mavlink_optical_flow::flow_comp_m_y, mavlink_optical_flow::flow_x, mavlink_optical_flow::flow_y, mavlink_optical_flow::ground_distance, optical_flow, mavlink_optical_flow::quality, mavlink_optical_flow::sensor_id, and mavlink_optical_flow::time_usec.
void px4flow_init | ( | void | ) |
Initialization function.
Definition at line 136 of file px4flow.c.
References mavlink_msg_req::callback, decode_heartbeat_msg(), decode_optical_flow_msg(), decode_optical_flow_rad_msg(), heartbeat, MAVLINK_OPTICAL_FLOW_MSG_ID, MAVLINK_OPTICAL_FLOW_RAD_MSG_ID, MAVLINK_OPTICAL_HEARTBEAT_MSG_ID, mavlink_register_msg(), mavlink_tp, mavlink_msg_req::msg, mavlink_msg_req::msg_id, optical_flow, optical_flow_rad, mavlink_message::payload, px4flow_compensate_rotation, px4flow_stddev, px4flow_update_agl, req_flow, req_flow_rad, and req_heartbeat.
|
extern |
Definition at line 1 of file px4flow.c.
Referenced by jevois_mavlink_event(), and px4flow_init().
|
extern |
Definition at line 1 of file px4flow.c.
Referenced by decode_optical_flow_msg(), px4flow_downlink(), and px4flow_init().
|
extern |
Definition at line 1 of file px4flow.c.
Referenced by px4flow_init().
|
extern |
Definition at line 71 of file px4flow.c.
Referenced by decode_optical_flow_msg(), and px4flow_init().
|
extern |
Definition at line 74 of file px4flow.c.
Referenced by decode_optical_flow_msg(), and px4flow_init().
|
extern |
Definition at line 68 of file px4flow.c.
Referenced by decode_optical_flow_msg(), and px4flow_init().