Classes | Defines | Typedefs | Functions
mavlink_msg_home_position.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_home_position_t

Defines

#define MAVLINK_MESSAGE_INFO_HOME_POSITION
#define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN   4
#define MAVLINK_MSG_ID_242_CRC   104
#define MAVLINK_MSG_ID_242_LEN   52
#define MAVLINK_MSG_ID_HOME_POSITION   242
#define MAVLINK_MSG_ID_HOME_POSITION_CRC   104
#define MAVLINK_MSG_ID_HOME_POSITION_LEN   52

Typedefs

typedef struct
__mavlink_home_position_t 
mavlink_home_position_t

Functions

static void mavlink_msg_home_position_decode (const mavlink_message_t *msg, mavlink_home_position_t *home_position)
 Decode a home_position message into a struct.
static uint16_t mavlink_msg_home_position_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_home_position_t *home_position)
 Encode a home_position struct.
static uint16_t mavlink_msg_home_position_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_home_position_t *home_position)
 Encode a home_position struct on a channel.
static int32_t mavlink_msg_home_position_get_altitude (const mavlink_message_t *msg)
 Get field altitude from home_position message.
static float mavlink_msg_home_position_get_approach_x (const mavlink_message_t *msg)
 Get field approach_x from home_position message.
static float mavlink_msg_home_position_get_approach_y (const mavlink_message_t *msg)
 Get field approach_y from home_position message.
static float mavlink_msg_home_position_get_approach_z (const mavlink_message_t *msg)
 Get field approach_z from home_position message.
static int32_t mavlink_msg_home_position_get_latitude (const mavlink_message_t *msg)
 Send a home_position message.
static int32_t mavlink_msg_home_position_get_longitude (const mavlink_message_t *msg)
 Get field longitude from home_position message.
static uint16_t mavlink_msg_home_position_get_q (const mavlink_message_t *msg, float *q)
 Get field q from home_position message.
static float mavlink_msg_home_position_get_x (const mavlink_message_t *msg)
 Get field x from home_position message.
static float mavlink_msg_home_position_get_y (const mavlink_message_t *msg)
 Get field y from home_position message.
static float mavlink_msg_home_position_get_z (const mavlink_message_t *msg)
 Get field z from home_position message.
static uint16_t mavlink_msg_home_position_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
 Pack a home_position message.
static uint16_t mavlink_msg_home_position_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
 Pack a home_position message on a channel.

Define Documentation

Value:
{ \
        "HOME_POSITION", \
        10, \
        {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \
         { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \
         { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \
         { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \
         { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \
         { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \
         { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \
         { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \
         { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \
         { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \
         } \
}

Definition at line 27 of file mavlink_msg_home_position.h.

Definition at line 25 of file mavlink_msg_home_position.h.

#define MAVLINK_MSG_ID_242_CRC   104

Definition at line 23 of file mavlink_msg_home_position.h.

#define MAVLINK_MSG_ID_242_LEN   52

Definition at line 20 of file mavlink_msg_home_position.h.

#define MAVLINK_MSG_ID_HOME_POSITION   242

Definition at line 3 of file mavlink_msg_home_position.h.

Definition at line 22 of file mavlink_msg_home_position.h.

Definition at line 19 of file mavlink_msg_home_position.h.


Typedef Documentation


Function Documentation

static void mavlink_msg_home_position_decode ( const mavlink_message_t msg,
mavlink_home_position_t home_position 
) [inline, static]

Decode a home_position message into a struct.

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

Definition at line 401 of file mavlink_msg_home_position.h.

static uint16_t mavlink_msg_home_position_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
const mavlink_home_position_t home_position 
) [inline, static]

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

Definition at line 167 of file mavlink_msg_home_position.h.

static uint16_t mavlink_msg_home_position_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
const mavlink_home_position_t home_position 
) [inline, static]

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

Definition at line 181 of file mavlink_msg_home_position.h.

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

Get field altitude from home_position message.

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

Definition at line 320 of file mavlink_msg_home_position.h.

static float mavlink_msg_home_position_get_approach_x ( const mavlink_message_t msg) [inline, static]

Get field approach_x from home_position message.

Returns:
Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.

Definition at line 370 of file mavlink_msg_home_position.h.

static float mavlink_msg_home_position_get_approach_y ( const mavlink_message_t msg) [inline, static]

Get field approach_y from home_position message.

Returns:
Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.

Definition at line 380 of file mavlink_msg_home_position.h.

static float mavlink_msg_home_position_get_approach_z ( const mavlink_message_t msg) [inline, static]

Get field approach_z from home_position message.

Returns:
Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.

Definition at line 390 of file mavlink_msg_home_position.h.

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

Send a home_position message.

Parameters:
chanMAVLink channel to send the message
latitudeLatitude (WGS84), in degrees * 1E7
longitudeLongitude (WGS84, in degrees * 1E7
altitudeAltitude (AMSL), in meters * 1000 (positive for up)
xLocal X position of this position in the local coordinate frame
yLocal Y position of this position in the local coordinate frame
zLocal Z position of this position in the local coordinate frame
qWorld to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
approach_xLocal X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_yLocal Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_zLocal Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. Get field latitude from home_position message
Returns:
Latitude (WGS84), in degrees * 1E7

Definition at line 300 of file mavlink_msg_home_position.h.

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

Get field longitude from home_position message.

Returns:
Longitude (WGS84, in degrees * 1E7

Definition at line 310 of file mavlink_msg_home_position.h.

static uint16_t mavlink_msg_home_position_get_q ( const mavlink_message_t msg,
float *  q 
) [inline, static]

Get field q from home_position message.

Returns:
World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground

Definition at line 360 of file mavlink_msg_home_position.h.

static float mavlink_msg_home_position_get_x ( const mavlink_message_t msg) [inline, static]

Get field x from home_position message.

Returns:
Local X position of this position in the local coordinate frame

Definition at line 330 of file mavlink_msg_home_position.h.

static float mavlink_msg_home_position_get_y ( const mavlink_message_t msg) [inline, static]

Get field y from home_position message.

Returns:
Local Y position of this position in the local coordinate frame

Definition at line 340 of file mavlink_msg_home_position.h.

static float mavlink_msg_home_position_get_z ( const mavlink_message_t msg) [inline, static]

Get field z from home_position message.

Returns:
Local Z position of this position in the local coordinate frame

Definition at line 350 of file mavlink_msg_home_position.h.

static uint16_t mavlink_msg_home_position_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
int32_t  latitude,
int32_t  longitude,
int32_t  altitude,
float  x,
float  y,
float  z,
const float *  q,
float  approach_x,
float  approach_y,
float  approach_z 
) [inline, static]

Pack a home_position 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
latitudeLatitude (WGS84), in degrees * 1E7
longitudeLongitude (WGS84, in degrees * 1E7
altitudeAltitude (AMSL), in meters * 1000 (positive for up)
xLocal X position of this position in the local coordinate frame
yLocal Y position of this position in the local coordinate frame
zLocal Z position of this position in the local coordinate frame
qWorld to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
approach_xLocal X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_yLocal Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_zLocal Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 62 of file mavlink_msg_home_position.h.

static uint16_t mavlink_msg_home_position_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
int32_t  latitude,
int32_t  longitude,
int32_t  altitude,
float  x,
float  y,
float  z,
const float *  q,
float  approach_x,
float  approach_y,
float  approach_z 
) [inline, static]

Pack a home_position 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
latitudeLatitude (WGS84), in degrees * 1E7
longitudeLongitude (WGS84, in degrees * 1E7
altitudeAltitude (AMSL), in meters * 1000 (positive for up)
xLocal X position of this position in the local coordinate frame
yLocal Y position of this position in the local coordinate frame
zLocal Z position of this position in the local coordinate frame
qWorld to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
approach_xLocal X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_yLocal Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_zLocal Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 119 of file mavlink_msg_home_position.h.



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