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) }, \
47 static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48 int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit,
const int16_t *data)
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51 char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
52 _mav_put_int32_t(buf, 0, lat);
53 _mav_put_int32_t(buf, 4, lon);
54 _mav_put_uint16_t(buf, 8, grid_spacing);
55 _mav_put_uint8_t(buf, 42, gridbit);
56 _mav_put_int16_t_array(buf, 10, data, 16);
57 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
64 mav_array_memcpy(packet.
data, data,
sizeof(int16_t)*16);
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
68 msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
70 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
72 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
89 static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
90 mavlink_message_t* msg,
91 int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,
const int16_t *data)
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
95 _mav_put_int32_t(buf, 0, lat);
96 _mav_put_int32_t(buf, 4, lon);
97 _mav_put_uint16_t(buf, 8, grid_spacing);
98 _mav_put_uint8_t(buf, 42, gridbit);
99 _mav_put_int16_t_array(buf, 10, data, 16);
100 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
107 mav_array_memcpy(packet.
data, data,
sizeof(int16_t)*16);
108 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
111 msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
112 #if MAVLINK_CRC_EXTRA
113 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
115 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
127 static 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)
129 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);
141 static 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)
143 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);
156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
158 static 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)
160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
161 char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
162 _mav_put_int32_t(buf, 0, lat);
163 _mav_put_int32_t(buf, 4, lon);
164 _mav_put_uint16_t(buf, 8, grid_spacing);
165 _mav_put_uint8_t(buf, 42, gridbit);
166 _mav_put_int16_t_array(buf, 10, data, 16);
167 #if MAVLINK_CRC_EXTRA
168 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
170 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
178 mav_array_memcpy(packet.
data, data,
sizeof(int16_t)*16);
179 #if MAVLINK_CRC_EXTRA
180 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (
const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
182 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (
const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
187 #if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
195 static 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)
197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
198 char *buf = (
char *)msgbuf;
199 _mav_put_int32_t(buf, 0, lat);
200 _mav_put_int32_t(buf, 4, lon);
201 _mav_put_uint16_t(buf, 8, grid_spacing);
202 _mav_put_uint8_t(buf, 42, gridbit);
203 _mav_put_int16_t_array(buf, 10, data, 16);
204 #if MAVLINK_CRC_EXTRA
205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
207 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
215 mav_array_memcpy(packet->
data, data,
sizeof(int16_t)*16);
216 #if MAVLINK_CRC_EXTRA
217 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (
const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (
const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
235 static inline int32_t mavlink_msg_terrain_data_get_lat(
const mavlink_message_t* msg)
237 return _MAV_RETURN_int32_t(msg, 0);
245 static inline int32_t mavlink_msg_terrain_data_get_lon(
const mavlink_message_t* msg)
247 return _MAV_RETURN_int32_t(msg, 4);
255 static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(
const mavlink_message_t* msg)
257 return _MAV_RETURN_uint16_t(msg, 8);
265 static inline uint8_t mavlink_msg_terrain_data_get_gridbit(
const mavlink_message_t* msg)
267 return _MAV_RETURN_uint8_t(msg, 42);
275 static inline uint16_t mavlink_msg_terrain_data_get_data(
const mavlink_message_t* msg, int16_t *data)
277 return _MAV_RETURN_int16_t_array(msg, data, 16, 10);
286 static inline void mavlink_msg_terrain_data_decode(
const mavlink_message_t* msg,
mavlink_terrain_data_t* terrain_data)
288 #if MAVLINK_NEED_BYTE_SWAP
289 terrain_data->
lat = mavlink_msg_terrain_data_get_lat(msg);
290 terrain_data->
lon = mavlink_msg_terrain_data_get_lon(msg);
291 terrain_data->
grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg);
292 mavlink_msg_terrain_data_get_data(msg, terrain_data->
data);
293 terrain_data->
gridbit = mavlink_msg_terrain_data_get_gridbit(msg);
295 memcpy(terrain_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
int16_t data[16]
Terrain data in meters AMSL.
Definition: mavlink_msg_terrain_data.h:10
int32_t lon
Longitude of SW corner of first grid (in degrees *10^7)
Definition: mavlink_msg_terrain_data.h:8
uint8_t gridbit
bit within the terrain request mask
Definition: mavlink_msg_terrain_data.h:11
int32_t lat
Latitude of SW corner of first grid (degrees *10^7)
Definition: mavlink_msg_terrain_data.h:7
Definition: mavlink_msg_terrain_data.h:5
uint16_t grid_spacing
Grid spacing in meters.
Definition: mavlink_msg_terrain_data.h:9