3 #define MAVLINK_MSG_ID_TERRAIN_REQUEST 133 13 #define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 14 #define MAVLINK_MSG_ID_133_LEN 18 16 #define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 17 #define MAVLINK_MSG_ID_133_CRC 6 21 #define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ 24 { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ 25 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ 26 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ 27 { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ 47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 86 mavlink_message_t* msg,
89 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 108 #if MAVLINK_CRC_EXTRA 151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 162 #if MAVLINK_CRC_EXTRA 174 #if MAVLINK_CRC_EXTRA 182 #if MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN 192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 193 char *buf = (
char *)msgbuf;
199 #if MAVLINK_CRC_EXTRA 211 #if MAVLINK_CRC_EXTRA 232 return _MAV_RETURN_int32_t(msg, 8);
242 return _MAV_RETURN_int32_t(msg, 12);
252 return _MAV_RETURN_uint16_t(msg, 16);
262 return _MAV_RETURN_uint64_t(msg, 0);
273 #if MAVLINK_NEED_BYTE_SWAP #define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN
static uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t *msg)
Get field mask from terrain_request message.
static uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t *msg)
Get field grid_spacing from terrain_request 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 MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
#define MAVLINK_MSG_ID_TERRAIN_REQUEST
#define _MAV_PAYLOAD(msg)
static int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t *msg)
Get field lon from terrain_request message.
struct __mavlink_terrain_request_t mavlink_terrain_request_t
static int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t *msg)
Send a terrain_request message.
static uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
Pack a terrain_request message on a channel.
static uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_terrain_request_t *terrain_request)
Encode a terrain_request struct on a channel.
#define _mav_put_uint16_t(buf, wire_offset, b)
static void mavlink_msg_terrain_request_decode(const mavlink_message_t *msg, mavlink_terrain_request_t *terrain_request)
Decode a terrain_request message into a struct.
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_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
Pack a terrain_request message.
static uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_terrain_request_t *terrain_request)
Encode a terrain_request struct.