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) }, \ 56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 104 mavlink_message_t* msg,
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 132 #if MAVLINK_CRC_EXTRA 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 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 225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 226 char *buf = (
char *)msgbuf;
235 #if MAVLINK_CRC_EXTRA 250 #if MAVLINK_CRC_EXTRA 271 return _MAV_RETURN_int32_t(msg, 0);
281 return _MAV_RETURN_int32_t(msg, 4);
291 return _MAV_RETURN_uint16_t(msg, 16);
301 return _MAV_RETURN_float(msg, 8);
311 return _MAV_RETURN_float(msg, 12);
321 return _MAV_RETURN_uint16_t(msg, 18);
331 return _MAV_RETURN_uint16_t(msg, 20);
342 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t *msg)
Get field lon from terrain_report message.
static void mavlink_msg_terrain_report_decode(const mavlink_message_t *msg, mavlink_terrain_report_t *terrain_report)
Decode a terrain_report message into a struct.
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_report_get_loaded(const mavlink_message_t *msg)
Get field loaded from terrain_report message.
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN
#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC
static uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t *msg)
Get field pending from terrain_report message.
#define _MAV_PAYLOAD(msg)
static 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)
Encode a terrain_report struct on a channel.
static 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)
Encode a terrain_report struct.
static float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t *msg)
Get field terrain_height from terrain_report message.
static uint16_t mavlink_msg_terrain_report_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 spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
Pack a terrain_report message on a channel.
#define _mav_put_uint16_t(buf, wire_offset, b)
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.
static float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t *msg)
Get field current_height from terrain_report message.
static uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t *msg)
Get field spacing from terrain_report message.
static uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
Pack a terrain_report message.
#define MAVLINK_MSG_ID_TERRAIN_REPORT
static int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t *msg)
Send a terrain_report message.