Classes | Macros | Typedefs | Functions
mavlink_msg_terrain_report.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_terrain_report_t
 

Macros

#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT
 
#define MAVLINK_MSG_ID_136_CRC   1
 
#define MAVLINK_MSG_ID_136_LEN   22
 
#define MAVLINK_MSG_ID_TERRAIN_REPORT   136
 
#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC   1
 
#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN   22
 

Typedefs

typedef struct __mavlink_terrain_report_t mavlink_terrain_report_t
 

Functions

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. More...
 
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. More...
 
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. More...
 
static float mavlink_msg_terrain_report_get_current_height (const mavlink_message_t *msg)
 Get field current_height from terrain_report message. More...
 
static int32_t mavlink_msg_terrain_report_get_lat (const mavlink_message_t *msg)
 Send a terrain_report message. More...
 
static uint16_t mavlink_msg_terrain_report_get_loaded (const mavlink_message_t *msg)
 Get field loaded from terrain_report message. More...
 
static int32_t mavlink_msg_terrain_report_get_lon (const mavlink_message_t *msg)
 Get field lon from terrain_report message. More...
 
static uint16_t mavlink_msg_terrain_report_get_pending (const mavlink_message_t *msg)
 Get field pending from terrain_report message. More...
 
static uint16_t mavlink_msg_terrain_report_get_spacing (const mavlink_message_t *msg)
 Get field spacing from terrain_report message. More...
 
static float mavlink_msg_terrain_report_get_terrain_height (const mavlink_message_t *msg)
 Get field terrain_height from terrain_report message. More...
 
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. More...
 
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. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT
Value:
{ \
"TERRAIN_REPORT", \
7, \
{ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \
{ "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \
{ "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \
{ "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \
{ "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \
{ "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_terrain_report.h.

#define MAVLINK_MSG_ID_136_CRC   1

Definition at line 20 of file mavlink_msg_terrain_report.h.

#define MAVLINK_MSG_ID_136_LEN   22

Definition at line 17 of file mavlink_msg_terrain_report.h.

#define MAVLINK_MSG_ID_TERRAIN_REPORT   136

Definition at line 3 of file mavlink_msg_terrain_report.h.

#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC   1

Definition at line 19 of file mavlink_msg_terrain_report.h.

#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN   22

Definition at line 16 of file mavlink_msg_terrain_report.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_terrain_report_decode ( const mavlink_message_t *  msg,
mavlink_terrain_report_t terrain_report 
)
inlinestatic

Decode a terrain_report message into a struct.

Parameters
msgThe message to decode
terrain_reportC-struct to decode the message contents into

Definition at line 340 of file mavlink_msg_terrain_report.h.

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 
)
inlinestatic

Encode a terrain_report struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
terrain_reportC-struct to read the message contents from

Definition at line 147 of file mavlink_msg_terrain_report.h.

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 
)
inlinestatic

Encode a terrain_report struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
terrain_reportC-struct to read the message contents from

Definition at line 161 of file mavlink_msg_terrain_report.h.

static float mavlink_msg_terrain_report_get_current_height ( const mavlink_message_t *  msg)
inlinestatic

Get field current_height from terrain_report message.

Returns
Current vehicle height above lat/lon terrain height (meters)

Definition at line 309 of file mavlink_msg_terrain_report.h.

static int32_t mavlink_msg_terrain_report_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Send a terrain_report message.

Parameters
chanMAVLink channel to send the message
latLatitude (degrees *10^7)
lonLongitude (degrees *10^7)
spacinggrid spacing (zero if terrain at this location unavailable)
terrain_heightTerrain height in meters AMSL
current_heightCurrent vehicle height above lat/lon terrain height (meters)
pendingNumber of 4x4 terrain blocks waiting to be received or read from disk
loadedNumber of 4x4 terrain blocks in memory Get field lat from terrain_report message
Returns
Latitude (degrees *10^7)

Definition at line 269 of file mavlink_msg_terrain_report.h.

static uint16_t mavlink_msg_terrain_report_get_loaded ( const mavlink_message_t *  msg)
inlinestatic

Get field loaded from terrain_report message.

Returns
Number of 4x4 terrain blocks in memory

Definition at line 329 of file mavlink_msg_terrain_report.h.

static int32_t mavlink_msg_terrain_report_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from terrain_report message.

Returns
Longitude (degrees *10^7)

Definition at line 279 of file mavlink_msg_terrain_report.h.

static uint16_t mavlink_msg_terrain_report_get_pending ( const mavlink_message_t *  msg)
inlinestatic

Get field pending from terrain_report message.

Returns
Number of 4x4 terrain blocks waiting to be received or read from disk

Definition at line 319 of file mavlink_msg_terrain_report.h.

static uint16_t mavlink_msg_terrain_report_get_spacing ( const mavlink_message_t *  msg)
inlinestatic

Get field spacing from terrain_report message.

Returns
grid spacing (zero if terrain at this location unavailable)

Definition at line 289 of file mavlink_msg_terrain_report.h.

static float mavlink_msg_terrain_report_get_terrain_height ( const mavlink_message_t *  msg)
inlinestatic

Get field terrain_height from terrain_report message.

Returns
Terrain height in meters AMSL

Definition at line 299 of file mavlink_msg_terrain_report.h.

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 
)
inlinestatic

Pack a terrain_report message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
latLatitude (degrees *10^7)
lonLongitude (degrees *10^7)
spacinggrid spacing (zero if terrain at this location unavailable)
terrain_heightTerrain height in meters AMSL
current_heightCurrent vehicle height above lat/lon terrain height (meters)
pendingNumber of 4x4 terrain blocks waiting to be received or read from disk
loadedNumber of 4x4 terrain blocks in memory
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_terrain_report.h.

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 
)
inlinestatic

Pack a terrain_report message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
latLatitude (degrees *10^7)
lonLongitude (degrees *10^7)
spacinggrid spacing (zero if terrain at this location unavailable)
terrain_heightTerrain height in meters AMSL
current_heightCurrent vehicle height above lat/lon terrain height (meters)
pendingNumber of 4x4 terrain blocks waiting to be received or read from disk
loadedNumber of 4x4 terrain blocks in memory
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_terrain_report.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:52