Classes | Macros | Typedefs | Functions
mavlink_msg_terrain_data.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_data_t
 

Macros

#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA
 
#define MAVLINK_MSG_ID_134_CRC   229
 
#define MAVLINK_MSG_ID_134_LEN   43
 
#define MAVLINK_MSG_ID_TERRAIN_DATA   134
 
#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC   229
 
#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN   43
 
#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN   16
 

Typedefs

typedef struct __mavlink_terrain_data_t mavlink_terrain_data_t
 

Functions

static void mavlink_msg_terrain_data_decode (const mavlink_message_t *msg, mavlink_terrain_data_t *terrain_data)
 Decode a terrain_data message into a struct. More...
 
static 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)
 Encode a terrain_data struct. More...
 
static 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)
 Encode a terrain_data struct on a channel. More...
 
static uint16_t mavlink_msg_terrain_data_get_data (const mavlink_message_t *msg, int16_t *data)
 Get field data from terrain_data message. More...
 
static uint16_t mavlink_msg_terrain_data_get_grid_spacing (const mavlink_message_t *msg)
 Get field grid_spacing from terrain_data message. More...
 
static uint8_t mavlink_msg_terrain_data_get_gridbit (const mavlink_message_t *msg)
 Get field gridbit from terrain_data message. More...
 
static int32_t mavlink_msg_terrain_data_get_lat (const mavlink_message_t *msg)
 Send a terrain_data message. More...
 
static int32_t mavlink_msg_terrain_data_get_lon (const mavlink_message_t *msg)
 Get field lon from terrain_data message. More...
 
static uint16_t mavlink_msg_terrain_data_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
 Pack a terrain_data message. More...
 
static uint16_t mavlink_msg_terrain_data_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 grid_spacing, uint8_t gridbit, const int16_t *data)
 Pack a terrain_data message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA
Value:
{ \
"TERRAIN_DATA", \
5, \
{ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \
{ "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \
{ "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \
{ "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 22 of file mavlink_msg_terrain_data.h.

#define MAVLINK_MSG_ID_134_CRC   229

Definition at line 18 of file mavlink_msg_terrain_data.h.

#define MAVLINK_MSG_ID_134_LEN   43

Definition at line 15 of file mavlink_msg_terrain_data.h.

#define MAVLINK_MSG_ID_TERRAIN_DATA   134

Definition at line 3 of file mavlink_msg_terrain_data.h.

#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC   229

Definition at line 17 of file mavlink_msg_terrain_data.h.

#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN   43

Definition at line 14 of file mavlink_msg_terrain_data.h.

#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN   16

Definition at line 20 of file mavlink_msg_terrain_data.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_terrain_data_decode ( const mavlink_message_t *  msg,
mavlink_terrain_data_t terrain_data 
)
inlinestatic

Decode a terrain_data message into a struct.

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

Definition at line 286 of file mavlink_msg_terrain_data.h.

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

Encode a terrain_data 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_dataC-struct to read the message contents from

Definition at line 127 of file mavlink_msg_terrain_data.h.

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

Encode a terrain_data 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_dataC-struct to read the message contents from

Definition at line 141 of file mavlink_msg_terrain_data.h.

static uint16_t mavlink_msg_terrain_data_get_data ( const mavlink_message_t *  msg,
int16_t *  data 
)
inlinestatic

Get field data from terrain_data message.

Returns
Terrain data in meters AMSL

Definition at line 275 of file mavlink_msg_terrain_data.h.

static uint16_t mavlink_msg_terrain_data_get_grid_spacing ( const mavlink_message_t *  msg)
inlinestatic

Get field grid_spacing from terrain_data message.

Returns
Grid spacing in meters

Definition at line 255 of file mavlink_msg_terrain_data.h.

static uint8_t mavlink_msg_terrain_data_get_gridbit ( const mavlink_message_t *  msg)
inlinestatic

Get field gridbit from terrain_data message.

Returns
bit within the terrain request mask

Definition at line 265 of file mavlink_msg_terrain_data.h.

static int32_t mavlink_msg_terrain_data_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Send a terrain_data message.

Parameters
chanMAVLink channel to send the message
latLatitude of SW corner of first grid (degrees *10^7)
lonLongitude of SW corner of first grid (in degrees *10^7)
grid_spacingGrid spacing in meters
gridbitbit within the terrain request mask
dataTerrain data in meters AMSL Get field lat from terrain_data message
Returns
Latitude of SW corner of first grid (degrees *10^7)

Definition at line 235 of file mavlink_msg_terrain_data.h.

static int32_t mavlink_msg_terrain_data_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from terrain_data message.

Returns
Longitude of SW corner of first grid (in degrees *10^7)

Definition at line 245 of file mavlink_msg_terrain_data.h.

static uint16_t mavlink_msg_terrain_data_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
int32_t  lat,
int32_t  lon,
uint16_t  grid_spacing,
uint8_t  gridbit,
const int16_t *  data 
)
inlinestatic

Pack a terrain_data 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 of SW corner of first grid (degrees *10^7)
lonLongitude of SW corner of first grid (in degrees *10^7)
grid_spacingGrid spacing in meters
gridbitbit within the terrain request mask
dataTerrain data in meters AMSL
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 47 of file mavlink_msg_terrain_data.h.

static uint16_t mavlink_msg_terrain_data_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  grid_spacing,
uint8_t  gridbit,
const int16_t *  data 
)
inlinestatic

Pack a terrain_data 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 of SW corner of first grid (degrees *10^7)
lonLongitude of SW corner of first grid (in degrees *10^7)
grid_spacingGrid spacing in meters
gridbitbit within the terrain request mask
dataTerrain data in meters AMSL
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 89 of file mavlink_msg_terrain_data.h.



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