Classes | Defines | Typedefs | Functions
mavlink_msg_set_gps_global_origin.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_set_gps_global_origin_t

Defines

#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN
#define MAVLINK_MSG_ID_48_CRC   41
#define MAVLINK_MSG_ID_48_LEN   13
#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN   48
#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC   41
#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN   13

Typedefs

typedef struct
__mavlink_set_gps_global_origin_t 
mavlink_set_gps_global_origin_t

Functions

static void mavlink_msg_set_gps_global_origin_decode (const mavlink_message_t *msg, mavlink_set_gps_global_origin_t *set_gps_global_origin)
 Decode a set_gps_global_origin message into a struct.
static uint16_t mavlink_msg_set_gps_global_origin_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_gps_global_origin_t *set_gps_global_origin)
 Encode a set_gps_global_origin struct.
static uint16_t mavlink_msg_set_gps_global_origin_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_gps_global_origin_t *set_gps_global_origin)
 Encode a set_gps_global_origin struct on a channel.
static int32_t mavlink_msg_set_gps_global_origin_get_altitude (const mavlink_message_t *msg)
 Get field altitude from set_gps_global_origin message.
static int32_t mavlink_msg_set_gps_global_origin_get_latitude (const mavlink_message_t *msg)
 Get field latitude from set_gps_global_origin message.
static int32_t mavlink_msg_set_gps_global_origin_get_longitude (const mavlink_message_t *msg)
 Get field longitude from set_gps_global_origin message.
static uint8_t mavlink_msg_set_gps_global_origin_get_target_system (const mavlink_message_t *msg)
 Send a set_gps_global_origin message.
static uint16_t mavlink_msg_set_gps_global_origin_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude)
 Pack a set_gps_global_origin message.
static uint16_t mavlink_msg_set_gps_global_origin_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude)
 Pack a set_gps_global_origin message on a channel.

Define Documentation

Value:
{ \
        "SET_GPS_GLOBAL_ORIGIN", \
        4, \
        {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \
         { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \
         { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \
         } \
}

Definition at line 21 of file mavlink_msg_set_gps_global_origin.h.

#define MAVLINK_MSG_ID_48_CRC   41

Definition at line 17 of file mavlink_msg_set_gps_global_origin.h.

#define MAVLINK_MSG_ID_48_LEN   13

Definition at line 14 of file mavlink_msg_set_gps_global_origin.h.

Definition at line 3 of file mavlink_msg_set_gps_global_origin.h.

Definition at line 16 of file mavlink_msg_set_gps_global_origin.h.

Definition at line 13 of file mavlink_msg_set_gps_global_origin.h.


Typedef Documentation


Function Documentation

static void mavlink_msg_set_gps_global_origin_decode ( const mavlink_message_t msg,
mavlink_set_gps_global_origin_t set_gps_global_origin 
) [inline, static]

Decode a set_gps_global_origin message into a struct.

Parameters:
msgThe message to decode
set_gps_global_originC-struct to decode the message contents into

Definition at line 271 of file mavlink_msg_set_gps_global_origin.h.

static uint16_t mavlink_msg_set_gps_global_origin_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
const mavlink_set_gps_global_origin_t set_gps_global_origin 
) [inline, static]

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

Definition at line 123 of file mavlink_msg_set_gps_global_origin.h.

static uint16_t mavlink_msg_set_gps_global_origin_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
const mavlink_set_gps_global_origin_t set_gps_global_origin 
) [inline, static]

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

Definition at line 137 of file mavlink_msg_set_gps_global_origin.h.

static int32_t mavlink_msg_set_gps_global_origin_get_altitude ( const mavlink_message_t msg) [inline, static]

Get field altitude from set_gps_global_origin message.

Returns:
Altitude (AMSL), in meters * 1000 (positive for up)

Definition at line 260 of file mavlink_msg_set_gps_global_origin.h.

static int32_t mavlink_msg_set_gps_global_origin_get_latitude ( const mavlink_message_t msg) [inline, static]

Get field latitude from set_gps_global_origin message.

Returns:
Latitude (WGS84), in degrees * 1E7

Definition at line 240 of file mavlink_msg_set_gps_global_origin.h.

static int32_t mavlink_msg_set_gps_global_origin_get_longitude ( const mavlink_message_t msg) [inline, static]

Get field longitude from set_gps_global_origin message.

Returns:
Longitude (WGS84, in degrees * 1E7

Definition at line 250 of file mavlink_msg_set_gps_global_origin.h.

static uint8_t mavlink_msg_set_gps_global_origin_get_target_system ( const mavlink_message_t msg) [inline, static]

Send a set_gps_global_origin message.

Parameters:
chanMAVLink channel to send the message
target_systemSystem ID
latitudeLatitude (WGS84), in degrees * 1E7
longitudeLongitude (WGS84, in degrees * 1E7
altitudeAltitude (AMSL), in meters * 1000 (positive for up) Get field target_system from set_gps_global_origin message
Returns:
System ID

Definition at line 230 of file mavlink_msg_set_gps_global_origin.h.

static uint16_t mavlink_msg_set_gps_global_origin_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
uint8_t  target_system,
int32_t  latitude,
int32_t  longitude,
int32_t  altitude 
) [inline, static]

Pack a set_gps_global_origin 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
target_systemSystem ID
latitudeLatitude (WGS84), in degrees * 1E7
longitudeLongitude (WGS84, in degrees * 1E7
altitudeAltitude (AMSL), in meters * 1000 (positive for up)
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_set_gps_global_origin.h.

static uint16_t mavlink_msg_set_gps_global_origin_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
uint8_t  target_system,
int32_t  latitude,
int32_t  longitude,
int32_t  altitude 
) [inline, static]

Pack a set_gps_global_origin 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
target_systemSystem ID
latitudeLatitude (WGS84), in degrees * 1E7
longitudeLongitude (WGS84, in degrees * 1E7
altitudeAltitude (AMSL), in meters * 1000 (positive for up)
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 85 of file mavlink_msg_set_gps_global_origin.h.



dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:36