3 #define MAVLINK_MSG_ID_TERRAIN_DATA 134 14 #define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 15 #define MAVLINK_MSG_ID_134_LEN 43 17 #define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 18 #define MAVLINK_MSG_ID_134_CRC 229 20 #define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16 22 #define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ 25 { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ 26 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ 27 { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ 28 { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ 29 { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ 50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 56 _mav_put_int16_t_array(buf, 10, data, 16);
90 mavlink_message_t* msg,
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 99 _mav_put_int16_t_array(buf, 10, data, 16);
112 #if MAVLINK_CRC_EXTRA 156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 166 _mav_put_int16_t_array(buf, 10, data, 16);
167 #if MAVLINK_CRC_EXTRA 179 #if MAVLINK_CRC_EXTRA 187 #if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN 197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 198 char *buf = (
char *)msgbuf;
203 _mav_put_int16_t_array(buf, 10, data, 16);
204 #if MAVLINK_CRC_EXTRA 216 #if MAVLINK_CRC_EXTRA 237 return _MAV_RETURN_int32_t(msg, 0);
247 return _MAV_RETURN_int32_t(msg, 4);
257 return _MAV_RETURN_uint16_t(msg, 8);
277 return _MAV_RETURN_int16_t_array(msg, data, 16, 10);
288 #if MAVLINK_NEED_BYTE_SWAP static int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t *msg)
Get field lon from terrain_data message.
static void mavlink_msg_terrain_data_decode(const mavlink_message_t *msg, mavlink_terrain_data_t *terrain_data)
Decode a terrain_data message into a struct.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
#define MAVLINK_MSG_ID_TERRAIN_DATA
static uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t *msg)
Get field grid_spacing from terrain_data 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 uint16_t mavlink_msg_terrain_data_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, uint8_t gridbit, const int16_t *data)
Pack a terrain_data message on a channel.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_terrain_data_t *terrain_data)
Encode a terrain_data struct.
#define _MAV_PAYLOAD(msg)
#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC
static uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t *msg)
Get field gridbit from terrain_data message.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
struct __mavlink_terrain_data_t mavlink_terrain_data_t
static int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t *msg)
Send a terrain_data message.
#define _mav_put_uint16_t(buf, wire_offset, b)
#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN
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_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_terrain_data_t *terrain_data)
Encode a terrain_data struct on a channel.
static uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t *msg, int16_t *data)
Get field data from terrain_data message.
static uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
Pack a terrain_data message.