4#define MAVLINK_MSG_ID_TERRAIN_DATA 134
7typedef struct __mavlink_terrain_data_t {
10 uint16_t grid_spacing;
13}) mavlink_terrain_data_t;
15#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43
16#define MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN 43
17#define MAVLINK_MSG_ID_134_LEN 43
18#define MAVLINK_MSG_ID_134_MIN_LEN 43
20#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229
21#define MAVLINK_MSG_ID_134_CRC 229
23#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16
25#if MAVLINK_COMMAND_24BIT
26#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \
30 { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \
31 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \
32 { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \
33 { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \
34 { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \
38#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \
41 { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \
42 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \
43 { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \
44 { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \
45 { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \
63static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
64 int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit,
const int16_t *data)
66#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
68 _mav_put_int32_t(buf, 0, lat);
69 _mav_put_int32_t(buf, 4, lon);
70 _mav_put_uint16_t(buf, 8, grid_spacing);
71 _mav_put_uint8_t(buf, 42, gridbit);
72 _mav_put_int16_t_array(buf, 10, data, 16);
73 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
75 mavlink_terrain_data_t packet;
78 packet.grid_spacing = grid_spacing;
79 packet.gridbit = gridbit;
80 mav_array_memcpy(packet.data, data,
sizeof(int16_t)*16);
81 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
84 msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
85 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
101static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
102 mavlink_message_t* msg,
103 int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,
const int16_t *data)
105#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
106 char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
107 _mav_put_int32_t(buf, 0, lat);
108 _mav_put_int32_t(buf, 4, lon);
109 _mav_put_uint16_t(buf, 8, grid_spacing);
110 _mav_put_uint8_t(buf, 42, gridbit);
111 _mav_put_int16_t_array(buf, 10, data, 16);
112 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
114 mavlink_terrain_data_t packet;
117 packet.grid_spacing = grid_spacing;
118 packet.gridbit = gridbit;
119 mav_array_memcpy(packet.data, data,
sizeof(int16_t)*16);
120 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
123 msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
124 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
135static inline 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)
137 return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data);
149static inline 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)
151 return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data);
164#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
166static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit,
const int16_t *data)
168#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
169 char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
170 _mav_put_int32_t(buf, 0, lat);
171 _mav_put_int32_t(buf, 4, lon);
172 _mav_put_uint16_t(buf, 8, grid_spacing);
173 _mav_put_uint8_t(buf, 42, gridbit);
174 _mav_put_int16_t_array(buf, 10, data, 16);
175 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
177 mavlink_terrain_data_t packet;
180 packet.grid_spacing = grid_spacing;
181 packet.gridbit = gridbit;
182 mav_array_memcpy(packet.data, data,
sizeof(int16_t)*16);
183 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (
const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
192static inline void mavlink_msg_terrain_data_send_struct(mavlink_channel_t chan,
const mavlink_terrain_data_t* terrain_data)
194#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
195 mavlink_msg_terrain_data_send(chan, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data);
197 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (
const char *)terrain_data, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
201#if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
209static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit,
const int16_t *data)
211#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
212 char *buf = (
char *)msgbuf;
213 _mav_put_int32_t(buf, 0, lat);
214 _mav_put_int32_t(buf, 4, lon);
215 _mav_put_uint16_t(buf, 8, grid_spacing);
216 _mav_put_uint8_t(buf, 42, gridbit);
217 _mav_put_int16_t_array(buf, 10, data, 16);
218 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
220 mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf;
223 packet->grid_spacing = grid_spacing;
224 packet->gridbit = gridbit;
225 mav_array_memcpy(packet->data, data,
sizeof(int16_t)*16);
226 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (
const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
241static inline int32_t mavlink_msg_terrain_data_get_lat(
const mavlink_message_t* msg)
243 return _MAV_RETURN_int32_t(msg, 0);
251static inline int32_t mavlink_msg_terrain_data_get_lon(
const mavlink_message_t* msg)
253 return _MAV_RETURN_int32_t(msg, 4);
261static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(
const mavlink_message_t* msg)
263 return _MAV_RETURN_uint16_t(msg, 8);
271static inline uint8_t mavlink_msg_terrain_data_get_gridbit(
const mavlink_message_t* msg)
273 return _MAV_RETURN_uint8_t(msg, 42);
281static inline uint16_t mavlink_msg_terrain_data_get_data(
const mavlink_message_t* msg, int16_t *data)
283 return _MAV_RETURN_int16_t_array(msg, data, 16, 10);
292static inline void mavlink_msg_terrain_data_decode(
const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data)
294#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
295 terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg);
296 terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg);
297 terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg);
298 mavlink_msg_terrain_data_get_data(msg, terrain_data->data);
299 terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg);
301 uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_DATA_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_DATA_LEN;
302 memset(terrain_data, 0, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
303 memcpy(terrain_data, _MAV_PAYLOAD(msg), len);