3 #define MAVLINK_MSG_ID_OPTICAL_FLOW 100 17 #define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 18 #define MAVLINK_MSG_ID_100_LEN 26 20 #define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 21 #define MAVLINK_MSG_ID_100_CRC 175 25 #define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ 28 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ 29 { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ 30 { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ 31 { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ 32 { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ 33 { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ 34 { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ 35 { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ 59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 110 mavlink_message_t* msg,
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 140 #if MAVLINK_CRC_EXTRA 157 return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->
time_usec, optical_flow->
sensor_id, optical_flow->
flow_x, optical_flow->
flow_y, optical_flow->
flow_comp_m_x, optical_flow->
flow_comp_m_y, optical_flow->
quality, optical_flow->
ground_distance);
171 return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->
time_usec, optical_flow->
sensor_id, optical_flow->
flow_x, optical_flow->
flow_y, optical_flow->
flow_comp_m_x, optical_flow->
flow_comp_m_y, optical_flow->
quality, optical_flow->
ground_distance);
187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 202 #if MAVLINK_CRC_EXTRA 218 #if MAVLINK_CRC_EXTRA 226 #if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN 236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 237 char *buf = (
char *)msgbuf;
247 #if MAVLINK_CRC_EXTRA 263 #if MAVLINK_CRC_EXTRA 284 return _MAV_RETURN_uint64_t(msg, 0);
304 return _MAV_RETURN_int16_t(msg, 20);
314 return _MAV_RETURN_int16_t(msg, 22);
324 return _MAV_RETURN_float(msg, 8);
334 return _MAV_RETURN_float(msg, 12);
354 return _MAV_RETURN_float(msg, 16);
365 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t *msg)
Get field quality from optical_flow message.
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN
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.
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.
#define MAVLINK_MSG_ID_OPTICAL_FLOW
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.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
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.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
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.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
#define _MAV_PAYLOAD(msg)
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.
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.
static int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t *msg)
Get field flow_x from optical_flow message.
static float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t *msg)
Get field ground_distance from optical_flow message.
static int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t *msg)
Get field flow_y from optical_flow message.
struct __mavlink_optical_flow_t mavlink_optical_flow_t
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
#define _mav_put_int16_t(buf, wire_offset, b)
static uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t *msg)
Get field sensor_id from optical_flow message.
#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC
static uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t *msg)
Send a optical_flow message.