3 #define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 17 #define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 18 #define MAVLINK_MSG_ID_132_LEN 14 20 #define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 21 #define MAVLINK_MSG_ID_132_CRC 85 25 #define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ 28 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ 29 { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ 30 { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ 31 { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ 32 { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ 33 { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ 34 { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ 35 { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ 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_distance_sensor_pack(system_id, component_id, msg, distance_sensor->
time_boot_ms, distance_sensor->
min_distance, distance_sensor->
max_distance, distance_sensor->
current_distance, distance_sensor->
type, distance_sensor->
id, distance_sensor->
orientation, distance_sensor->
covariance);
171 return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->
time_boot_ms, distance_sensor->
min_distance, distance_sensor->
max_distance, distance_sensor->
current_distance, distance_sensor->
type, distance_sensor->
id, distance_sensor->
orientation, distance_sensor->
covariance);
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_DISTANCE_SENSOR_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_uint32_t(msg, 0);
294 return _MAV_RETURN_uint16_t(msg, 4);
304 return _MAV_RETURN_uint16_t(msg, 6);
314 return _MAV_RETURN_uint16_t(msg, 8);
365 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_distance_sensor_t *distance_sensor)
Encode a distance_sensor struct.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t *msg)
Get field max_distance from distance_sensor message.
static uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t *msg)
Get field orientation from distance_sensor 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.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t *msg)
Get field current_distance from distance_sensor message.
static uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
Pack a distance_sensor message on a channel.
static uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
Pack a distance_sensor message.
#define _MAV_PAYLOAD(msg)
static uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t *msg)
Get field covariance from distance_sensor message.
static uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t *msg)
Get field id from distance_sensor message.
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC
static void mavlink_msg_distance_sensor_decode(const mavlink_message_t *msg, mavlink_distance_sensor_t *distance_sensor)
Decode a distance_sensor message into a struct.
#define MAVLINK_MSG_ID_DISTANCE_SENSOR
struct __mavlink_distance_sensor_t mavlink_distance_sensor_t
uint16_t current_distance
static uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t *msg)
Send a distance_sensor message.
#define _mav_put_uint16_t(buf, wire_offset, b)
static uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_distance_sensor_t *distance_sensor)
Encode a distance_sensor struct on a channel.
static uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t *msg)
Get field type from distance_sensor message.
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.
static uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t *msg)
Get field min_distance from distance_sensor message.
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN
#define _mav_put_uint32_t(buf, wire_offset, b)