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
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
132 #if MAVLINK_CRC_EXTRA
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
192 #if MAVLINK_CRC_EXTRA
207 #if MAVLINK_CRC_EXTRA
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;
235 #if MAVLINK_CRC_EXTRA
250 #if MAVLINK_CRC_EXTRA
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);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
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
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.
Definition: mavlink_helpers.h:105
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:142
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN
Definition: mavlink_msg_terrain_report.h:16
int32_t lat
Latitude (degrees *10^7)
Definition: mavlink_msg_terrain_report.h:7
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC
Definition: mavlink_msg_terrain_report.h:19
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
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
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
struct __mavlink_terrain_report_t mavlink_terrain_report_t
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.
Definition: mavlink_helpers.h:71
#define MAVLINK_MSG_ID_TERRAIN_REPORT
Definition: mavlink_msg_terrain_report.h:3