Go to the source code of this file.
Classes | |
struct | __mavlink_optical_flow_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_OPTICAL_FLOW |
#define | MAVLINK_MSG_ID_100_CRC 175 |
#define | MAVLINK_MSG_ID_100_LEN 26 |
#define | MAVLINK_MSG_ID_OPTICAL_FLOW 100 |
#define | MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 |
#define | MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 |
Typedefs | |
typedef struct __mavlink_optical_flow_t | mavlink_optical_flow_t |
Functions | |
static void | mavlink_msg_optical_flow_decode (const mavlink_message_t *msg, mavlink_optical_flow_t *optical_flow) |
Decode a optical_flow message into a struct. More... | |
static uint16_t | mavlink_msg_optical_flow_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_optical_flow_t *optical_flow) |
Encode a optical_flow struct. More... | |
static uint16_t | mavlink_msg_optical_flow_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_optical_flow_t *optical_flow) |
Encode a optical_flow struct on a channel. More... | |
static float | mavlink_msg_optical_flow_get_flow_comp_m_x (const mavlink_message_t *msg) |
Get field flow_comp_m_x from optical_flow message. More... | |
static float | mavlink_msg_optical_flow_get_flow_comp_m_y (const mavlink_message_t *msg) |
Get field flow_comp_m_y from optical_flow message. More... | |
static int16_t | mavlink_msg_optical_flow_get_flow_x (const mavlink_message_t *msg) |
Get field flow_x from optical_flow message. More... | |
static int16_t | mavlink_msg_optical_flow_get_flow_y (const mavlink_message_t *msg) |
Get field flow_y from optical_flow message. More... | |
static float | mavlink_msg_optical_flow_get_ground_distance (const mavlink_message_t *msg) |
Get field ground_distance from optical_flow message. More... | |
static uint8_t | mavlink_msg_optical_flow_get_quality (const mavlink_message_t *msg) |
Get field quality from optical_flow message. More... | |
static uint8_t | mavlink_msg_optical_flow_get_sensor_id (const mavlink_message_t *msg) |
Get field sensor_id from optical_flow message. More... | |
static uint64_t | mavlink_msg_optical_flow_get_time_usec (const mavlink_message_t *msg) |
Send a optical_flow message. More... | |
static uint16_t | mavlink_msg_optical_flow_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) |
Pack a optical_flow message. More... | |
static uint16_t | mavlink_msg_optical_flow_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) |
Pack a optical_flow message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW |
Definition at line 25 of file mavlink_msg_optical_flow.h.
#define MAVLINK_MSG_ID_100_CRC 175 |
Definition at line 21 of file mavlink_msg_optical_flow.h.
#define MAVLINK_MSG_ID_100_LEN 26 |
Definition at line 18 of file mavlink_msg_optical_flow.h.
#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 |
Definition at line 3 of file mavlink_msg_optical_flow.h.
#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 |
Definition at line 20 of file mavlink_msg_optical_flow.h.
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 |
Definition at line 17 of file mavlink_msg_optical_flow.h.
typedef struct __mavlink_optical_flow_t mavlink_optical_flow_t |
|
inlinestatic |
Decode a optical_flow message into a struct.
msg | The message to decode |
optical_flow | C-struct to decode the message contents into |
Definition at line 363 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Encode a optical_flow struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
optical_flow | C-struct to read the message contents from |
Definition at line 155 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Encode a optical_flow struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
optical_flow | C-struct to read the message contents from |
Definition at line 169 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Get field flow_comp_m_x from optical_flow message.
Definition at line 322 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Get field flow_comp_m_y from optical_flow message.
Definition at line 332 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Get field flow_x from optical_flow message.
Definition at line 302 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Get field flow_y from optical_flow message.
Definition at line 312 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Get field ground_distance from optical_flow message.
Definition at line 352 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Get field quality from optical_flow message.
Definition at line 342 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Get field sensor_id from optical_flow message.
Definition at line 292 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Send a optical_flow message.
chan | MAVLink channel to send the message |
time_usec | Timestamp (UNIX) |
sensor_id | Sensor ID |
flow_x | Flow in pixels * 10 in x-sensor direction (dezi-pixels) |
flow_y | Flow in pixels * 10 in y-sensor direction (dezi-pixels) |
flow_comp_m_x | Flow in meters in x-sensor direction, angular-speed compensated |
flow_comp_m_y | Flow in meters in y-sensor direction, angular-speed compensated |
quality | Optical flow quality / confidence. 0: bad, 255: maximum quality |
ground_distance | Ground distance in meters. Positive value: distance known. Negative value: Unknown distance Get field time_usec from optical_flow message |
Definition at line 282 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Pack a optical_flow message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
time_usec | Timestamp (UNIX) |
sensor_id | Sensor ID |
flow_x | Flow in pixels * 10 in x-sensor direction (dezi-pixels) |
flow_y | Flow in pixels * 10 in y-sensor direction (dezi-pixels) |
flow_comp_m_x | Flow in meters in x-sensor direction, angular-speed compensated |
flow_comp_m_y | Flow in meters in y-sensor direction, angular-speed compensated |
quality | Optical flow quality / confidence. 0: bad, 255: maximum quality |
ground_distance | Ground distance in meters. Positive value: distance known. Negative value: Unknown distance |
Definition at line 56 of file mavlink_msg_optical_flow.h.
|
inlinestatic |
Pack a optical_flow message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
time_usec | Timestamp (UNIX) |
sensor_id | Sensor ID |
flow_x | Flow in pixels * 10 in x-sensor direction (dezi-pixels) |
flow_y | Flow in pixels * 10 in y-sensor direction (dezi-pixels) |
flow_comp_m_x | Flow in meters in x-sensor direction, angular-speed compensated |
flow_comp_m_y | Flow in meters in y-sensor direction, angular-speed compensated |
quality | Optical flow quality / confidence. 0: bad, 255: maximum quality |
ground_distance | Ground distance in meters. Positive value: distance known. Negative value: Unknown distance |
Definition at line 109 of file mavlink_msg_optical_flow.h.