Classes | Macros | Typedefs | Functions
mavlink_msg_terrain_request.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_request_t
 

Macros

#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST
 
#define MAVLINK_MSG_ID_133_CRC   6
 
#define MAVLINK_MSG_ID_133_LEN   18
 
#define MAVLINK_MSG_ID_TERRAIN_REQUEST   133
 
#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC   6
 
#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN   18
 

Typedefs

typedef struct __mavlink_terrain_request_t mavlink_terrain_request_t
 

Functions

static void mavlink_msg_terrain_request_decode (const mavlink_message_t *msg, mavlink_terrain_request_t *terrain_request)
 Decode a terrain_request message into a struct. More...
 
static uint16_t mavlink_msg_terrain_request_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_terrain_request_t *terrain_request)
 Encode a terrain_request struct. More...
 
static uint16_t mavlink_msg_terrain_request_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_terrain_request_t *terrain_request)
 Encode a terrain_request struct on a channel. More...
 
static uint16_t mavlink_msg_terrain_request_get_grid_spacing (const mavlink_message_t *msg)
 Get field grid_spacing from terrain_request message. More...
 
static int32_t mavlink_msg_terrain_request_get_lat (const mavlink_message_t *msg)
 Send a terrain_request message. More...
 
static int32_t mavlink_msg_terrain_request_get_lon (const mavlink_message_t *msg)
 Get field lon from terrain_request message. More...
 
static uint64_t mavlink_msg_terrain_request_get_mask (const mavlink_message_t *msg)
 Get field mask from terrain_request message. More...
 
static uint16_t mavlink_msg_terrain_request_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
 Pack a terrain_request message. More...
 
static uint16_t mavlink_msg_terrain_request_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, uint64_t mask)
 Pack a terrain_request message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST
Value:
{ \
"TERRAIN_REQUEST", \
4, \
{ { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \
{ "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_terrain_request.h.

#define MAVLINK_MSG_ID_133_CRC   6

Definition at line 17 of file mavlink_msg_terrain_request.h.

#define MAVLINK_MSG_ID_133_LEN   18

Definition at line 14 of file mavlink_msg_terrain_request.h.

#define MAVLINK_MSG_ID_TERRAIN_REQUEST   133

Definition at line 3 of file mavlink_msg_terrain_request.h.

#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC   6

Definition at line 16 of file mavlink_msg_terrain_request.h.

#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN   18

Definition at line 13 of file mavlink_msg_terrain_request.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_terrain_request_decode ( const mavlink_message_t *  msg,
mavlink_terrain_request_t terrain_request 
)
inlinestatic

Decode a terrain_request message into a struct.

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

Definition at line 271 of file mavlink_msg_terrain_request.h.

static uint16_t mavlink_msg_terrain_request_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_terrain_request_t terrain_request 
)
inlinestatic

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

Definition at line 123 of file mavlink_msg_terrain_request.h.

static uint16_t mavlink_msg_terrain_request_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_terrain_request_t terrain_request 
)
inlinestatic

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

Definition at line 137 of file mavlink_msg_terrain_request.h.

static uint16_t mavlink_msg_terrain_request_get_grid_spacing ( const mavlink_message_t *  msg)
inlinestatic

Get field grid_spacing from terrain_request message.

Returns
Grid spacing in meters

Definition at line 250 of file mavlink_msg_terrain_request.h.

static int32_t mavlink_msg_terrain_request_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Send a terrain_request 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
maskBitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) Get field lat from terrain_request message
Returns
Latitude of SW corner of first grid (degrees *10^7)

Definition at line 230 of file mavlink_msg_terrain_request.h.

static int32_t mavlink_msg_terrain_request_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from terrain_request message.

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

Definition at line 240 of file mavlink_msg_terrain_request.h.

static uint64_t mavlink_msg_terrain_request_get_mask ( const mavlink_message_t *  msg)
inlinestatic

Get field mask from terrain_request message.

Returns
Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)

Definition at line 260 of file mavlink_msg_terrain_request.h.

static uint16_t mavlink_msg_terrain_request_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
int32_t  lat,
int32_t  lon,
uint16_t  grid_spacing,
uint64_t  mask 
)
inlinestatic

Pack a terrain_request 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
maskBitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_terrain_request.h.

static uint16_t mavlink_msg_terrain_request_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,
uint64_t  mask 
)
inlinestatic

Pack a terrain_request 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
maskBitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 85 of file mavlink_msg_terrain_request.h.



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