3 #define MAVLINK_MSG_ID_TERRAIN_REPORT 136
16 #define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22
17 #define MAVLINK_MSG_ID_136_LEN 22
19 #define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1
20 #define MAVLINK_MSG_ID_136_CRC 1
24 #define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \
27 { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \
28 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \
29 { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \
30 { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \
31 { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \
32 { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \
33 { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \
53 static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54 int32_t lat, int32_t lon, uint16_t spacing,
float terrain_height,
float current_height, uint16_t pending, uint16_t loaded)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
57 char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
58 _mav_put_int32_t(buf, 0, lat);
59 _mav_put_int32_t(buf, 4, lon);
60 _mav_put_float(buf, 8, terrain_height);
61 _mav_put_float(buf, 12, current_height);
62 _mav_put_uint16_t(buf, 16, spacing);
63 _mav_put_uint16_t(buf, 18, pending);
64 _mav_put_uint16_t(buf, 20, loaded);
66 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
77 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
80 msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT;
82 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
84 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
103 static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104 mavlink_message_t* msg,
105 int32_t lat,int32_t lon,uint16_t spacing,
float terrain_height,
float current_height,uint16_t pending,uint16_t loaded)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
109 _mav_put_int32_t(buf, 0, lat);
110 _mav_put_int32_t(buf, 4, lon);
111 _mav_put_float(buf, 8, terrain_height);
112 _mav_put_float(buf, 12, current_height);
113 _mav_put_uint16_t(buf, 16, spacing);
114 _mav_put_uint16_t(buf, 18, pending);
115 _mav_put_uint16_t(buf, 20, loaded);
117 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
128 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
131 msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT;
132 #if MAVLINK_CRC_EXTRA
133 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
135 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
147 static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_terrain_report_t* terrain_report)
161 static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_terrain_report_t* terrain_report)
163 return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->
lat, terrain_report->
lon, terrain_report->
spacing, terrain_report->
terrain_height, terrain_report->
current_height, terrain_report->
pending, terrain_report->
loaded);
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180 static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing,
float terrain_height,
float current_height, uint16_t pending, uint16_t loaded)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
184 _mav_put_int32_t(buf, 0, lat);
185 _mav_put_int32_t(buf, 4, lon);
186 _mav_put_float(buf, 8, terrain_height);
187 _mav_put_float(buf, 12, current_height);
188 _mav_put_uint16_t(buf, 16, spacing);
189 _mav_put_uint16_t(buf, 18, pending);
190 _mav_put_uint16_t(buf, 20, loaded);
192 #if MAVLINK_CRC_EXTRA
193 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
195 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
207 #if MAVLINK_CRC_EXTRA
208 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (
const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
210 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (
const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
215 #if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
223 static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing,
float terrain_height,
float current_height, uint16_t pending, uint16_t loaded)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226 char *buf = (
char *)msgbuf;
227 _mav_put_int32_t(buf, 0, lat);
228 _mav_put_int32_t(buf, 4, lon);
229 _mav_put_float(buf, 8, terrain_height);
230 _mav_put_float(buf, 12, current_height);
231 _mav_put_uint16_t(buf, 16, spacing);
232 _mav_put_uint16_t(buf, 18, pending);
233 _mav_put_uint16_t(buf, 20, loaded);
235 #if MAVLINK_CRC_EXTRA
236 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
250 #if MAVLINK_CRC_EXTRA
251 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (
const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
253 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (
const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
269 static inline int32_t mavlink_msg_terrain_report_get_lat(
const mavlink_message_t* msg)
271 return _MAV_RETURN_int32_t(msg, 0);
279 static inline int32_t mavlink_msg_terrain_report_get_lon(
const mavlink_message_t* msg)
281 return _MAV_RETURN_int32_t(msg, 4);
289 static inline uint16_t mavlink_msg_terrain_report_get_spacing(
const mavlink_message_t* msg)
291 return _MAV_RETURN_uint16_t(msg, 16);
299 static inline float mavlink_msg_terrain_report_get_terrain_height(
const mavlink_message_t* msg)
301 return _MAV_RETURN_float(msg, 8);
309 static inline float mavlink_msg_terrain_report_get_current_height(
const mavlink_message_t* msg)
311 return _MAV_RETURN_float(msg, 12);
319 static inline uint16_t mavlink_msg_terrain_report_get_pending(
const mavlink_message_t* msg)
321 return _MAV_RETURN_uint16_t(msg, 18);
329 static inline uint16_t mavlink_msg_terrain_report_get_loaded(
const mavlink_message_t* msg)
331 return _MAV_RETURN_uint16_t(msg, 20);
340 static inline void mavlink_msg_terrain_report_decode(
const mavlink_message_t* msg,
mavlink_terrain_report_t* terrain_report)
342 #if MAVLINK_NEED_BYTE_SWAP
343 terrain_report->
lat = mavlink_msg_terrain_report_get_lat(msg);
344 terrain_report->
lon = mavlink_msg_terrain_report_get_lon(msg);
345 terrain_report->
terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg);
346 terrain_report->
current_height = mavlink_msg_terrain_report_get_current_height(msg);
347 terrain_report->
spacing = mavlink_msg_terrain_report_get_spacing(msg);
348 terrain_report->
pending = mavlink_msg_terrain_report_get_pending(msg);
349 terrain_report->
loaded = mavlink_msg_terrain_report_get_loaded(msg);
351 memcpy(terrain_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
uint16_t pending
Number of 4x4 terrain blocks waiting to be received or read from disk.
Definition: mavlink_msg_terrain_report.h:12
float terrain_height
Terrain height in meters AMSL.
Definition: mavlink_msg_terrain_report.h:9
int32_t lat
Latitude (degrees *10^7)
Definition: mavlink_msg_terrain_report.h:7
float current_height
Current vehicle height above lat/lon terrain height (meters)
Definition: mavlink_msg_terrain_report.h:10
uint16_t loaded
Number of 4x4 terrain blocks in memory.
Definition: mavlink_msg_terrain_report.h:13
Definition: mavlink_msg_terrain_report.h:5
uint16_t spacing
grid spacing (zero if terrain at this location unavailable)
Definition: mavlink_msg_terrain_report.h:11
int32_t lon
Longitude (degrees *10^7)
Definition: mavlink_msg_terrain_report.h:8