Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
driver for the optical flow sensor PX4FLOW More...
#include "modules/optical_flow/px4flow.h"
#include "modules/datalink/mavlink_decoder.h"
#include "modules/core/abi.h"
#include "state.h"
#include "mcu_periph/uart.h"
#include "pprzlink/messages.h"
#include "modules/datalink/downlink.h"
Go to the source code of this file.
Macros | |
#define | MAVLINK_OPTICAL_HEARTBEAT_MSG_ID 0 |
#define | MAVLINK_OPTICAL_FLOW_MSG_ID 100 |
#define | MAVLINK_OPTICAL_FLOW_RAD_MSG_ID 106 |
#define | PX4FLOW_QUALITY_THRESHOLD 0.1 |
Functions | |
static void | decode_optical_flow_msg (struct mavlink_message *msg) |
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 as well as OPTICAL_FLOW message. More... | |
static void | decode_heartbeat_msg (struct mavlink_message *msg) |
void | px4flow_init (void) |
Initialization function. More... | |
void | px4flow_downlink (void) |
Downlink message for debug. More... | |
Variables | |
struct mavlink_heartbeat | heartbeat |
struct mavlink_optical_flow | optical_flow |
struct mavlink_optical_flow_rad | optical_flow_rad |
struct mavlink_msg_req | req_flow |
struct mavlink_msg_req | req_flow_rad |
struct mavlink_msg_req | req_heartbeat |
bool | px4flow_update_agl |
bool | px4flow_compensate_rotation |
float | px4flow_stddev |
driver for the optical flow sensor PX4FLOW
driver for the optical flow sensor PX4FLOW over i2c
Sensor from the PIXHAWK project
Definition in file px4flow.c.
|
static |
Definition at line 128 of file px4flow.c.
Referenced by px4flow_init().
|
static |
Definition at line 78 of file px4flow.c.
References AGL_SONAR_PX4FLOW_ID, mavlink_optical_flow::distance, mavlink_optical_flow::flow_comp_m_x, mavlink_optical_flow::flow_comp_m_y, get_sys_time_usec(), mavlink_optical_flow::ground_distance, optical_flow, FloatEulers::phi, px4flow_compensate_rotation, PX4FLOW_QUALITY_THRESHOLD, px4flow_stddev, px4flow_update_agl, mavlink_optical_flow::quality, stateGetNedToBodyEulers_f(), FloatEulers::theta, mavlink_optical_flow::time_usec, and VEL_PX4FLOW_ID.
Referenced by px4flow_init().
|
static |
According to https://pixhawk.org/modules/px4flow the PX4flow module outputs OPTICAL_FLOW_RAD message as well as OPTICAL_FLOW message.
However, on my camera only OPTICAL_FLOW is received. Maybe different firmwares send different messages?
Definition at line 123 of file px4flow.c.
Referenced by px4flow_init().
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.
struct mavlink_heartbeat heartbeat |
Definition at line 1 of file px4flow.c.
Referenced by jevois_mavlink_event(), and px4flow_init().
struct mavlink_optical_flow optical_flow |
Definition at line 1 of file px4flow.c.
Referenced by decode_optical_flow_msg(), px4flow_downlink(), and px4flow_init().
struct mavlink_optical_flow_rad optical_flow_rad |
Definition at line 1 of file px4flow.c.
Referenced by px4flow_init().
bool px4flow_compensate_rotation |
Definition at line 71 of file px4flow.c.
Referenced by decode_optical_flow_msg(), and px4flow_init().
float px4flow_stddev |
Definition at line 74 of file px4flow.c.
Referenced by decode_optical_flow_msg(), and px4flow_init().
bool px4flow_update_agl |
Definition at line 68 of file px4flow.c.
Referenced by decode_optical_flow_msg(), and px4flow_init().
struct mavlink_msg_req req_flow |
Definition at line 1 of file px4flow.c.
Referenced by px4flow_init().
struct mavlink_msg_req req_flow_rad |
Definition at line 1 of file px4flow.c.
Referenced by px4flow_init().
struct mavlink_msg_req req_heartbeat |
Definition at line 1 of file px4flow.c.
Referenced by px4flow_init().