Classes | Macros | Typedefs | Functions
mavlink_msg_set_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_set_home_position_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION
 
#define MAVLINK_MSG_ID_243_CRC   85
 
#define MAVLINK_MSG_ID_243_LEN   53
 
#define MAVLINK_MSG_ID_SET_HOME_POSITION   243
 
#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC   85
 
#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN   53
 
#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN   4
 

Typedefs

typedef struct __mavlink_set_home_position_t mavlink_set_home_position_t
 

Functions

static void mavlink_msg_set_home_position_decode (const mavlink_message_t *msg, mavlink_set_home_position_t *set_home_position)
 Decode a set_home_position message into a struct. More...
 
static uint16_t mavlink_msg_set_home_position_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_home_position_t *set_home_position)
 Encode a set_home_position struct. More...
 
static uint16_t mavlink_msg_set_home_position_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_home_position_t *set_home_position)
 Encode a set_home_position struct on a channel. More...
 
static int32_t mavlink_msg_set_home_position_get_altitude (const mavlink_message_t *msg)
 Get field altitude from set_home_position message. More...
 
static float mavlink_msg_set_home_position_get_approach_x (const mavlink_message_t *msg)
 Get field approach_x from set_home_position message. More...
 
static float mavlink_msg_set_home_position_get_approach_y (const mavlink_message_t *msg)
 Get field approach_y from set_home_position message. More...
 
static float mavlink_msg_set_home_position_get_approach_z (const mavlink_message_t *msg)
 Get field approach_z from set_home_position message. More...
 
static int32_t mavlink_msg_set_home_position_get_latitude (const mavlink_message_t *msg)
 Get field latitude from set_home_position message. More...
 
static int32_t mavlink_msg_set_home_position_get_longitude (const mavlink_message_t *msg)
 Get field longitude from set_home_position message. More...
 
static uint16_t mavlink_msg_set_home_position_get_q (const mavlink_message_t *msg, float *q)
 Get field q from set_home_position message. More...
 
static uint8_t mavlink_msg_set_home_position_get_target_system (const mavlink_message_t *msg)
 Send a set_home_position message. More...
 
static float mavlink_msg_set_home_position_get_x (const mavlink_message_t *msg)
 Get field x from set_home_position message. More...
 
static float mavlink_msg_set_home_position_get_y (const mavlink_message_t *msg)
 Get field y from set_home_position message. More...
 
static float mavlink_msg_set_home_position_get_z (const mavlink_message_t *msg)
 Get field z from set_home_position message. More...
 
static uint16_t mavlink_msg_set_home_position_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, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
 Pack a set_home_position message. More...
 
static uint16_t mavlink_msg_set_home_position_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, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
 Pack a set_home_position message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION
Value:
{ \
"SET_HOME_POSITION", \
11, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \
{ "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \
{ "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \
{ "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \
} \
}
float altitude
Definition: ms4525.c:41
#define NULL
Definition: usbd_def.h:50

Definition at line 28 of file mavlink_msg_set_home_position.h.

#define MAVLINK_MSG_ID_243_CRC   85

Definition at line 24 of file mavlink_msg_set_home_position.h.

#define MAVLINK_MSG_ID_243_LEN   53

Definition at line 21 of file mavlink_msg_set_home_position.h.

#define MAVLINK_MSG_ID_SET_HOME_POSITION   243

Definition at line 3 of file mavlink_msg_set_home_position.h.

#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC   85

Definition at line 23 of file mavlink_msg_set_home_position.h.

#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN   53

Definition at line 20 of file mavlink_msg_set_home_position.h.

#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN   4

Definition at line 26 of file mavlink_msg_set_home_position.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_set_home_position_decode ( const mavlink_message_t *  msg,
mavlink_set_home_position_t set_home_position 
)
inlinestatic

Decode a set_home_position message into a struct.

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

Definition at line 424 of file mavlink_msg_set_home_position.h.

static uint16_t mavlink_msg_set_home_position_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_set_home_position_t set_home_position 
)
inlinestatic

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

Definition at line 175 of file mavlink_msg_set_home_position.h.

static uint16_t mavlink_msg_set_home_position_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_set_home_position_t set_home_position 
)
inlinestatic

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

Definition at line 189 of file mavlink_msg_set_home_position.h.

static int32_t mavlink_msg_set_home_position_get_altitude ( const mavlink_message_t *  msg)
inlinestatic

Get field altitude from set_home_position message.

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

Definition at line 343 of file mavlink_msg_set_home_position.h.

static float mavlink_msg_set_home_position_get_approach_x ( const mavlink_message_t *  msg)
inlinestatic

Get field approach_x from set_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 393 of file mavlink_msg_set_home_position.h.

static float mavlink_msg_set_home_position_get_approach_y ( const mavlink_message_t *  msg)
inlinestatic

Get field approach_y from set_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 403 of file mavlink_msg_set_home_position.h.

static float mavlink_msg_set_home_position_get_approach_z ( const mavlink_message_t *  msg)
inlinestatic

Get field approach_z from set_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 413 of file mavlink_msg_set_home_position.h.

static int32_t mavlink_msg_set_home_position_get_latitude ( const mavlink_message_t *  msg)
inlinestatic

Get field latitude from set_home_position message.

Returns
Latitude (WGS84), in degrees * 1E7

Definition at line 323 of file mavlink_msg_set_home_position.h.

static int32_t mavlink_msg_set_home_position_get_longitude ( const mavlink_message_t *  msg)
inlinestatic

Get field longitude from set_home_position message.

Returns
Longitude (WGS84, in degrees * 1E7

Definition at line 333 of file mavlink_msg_set_home_position.h.

static uint16_t mavlink_msg_set_home_position_get_q ( const mavlink_message_t *  msg,
float *  q 
)
inlinestatic

Get field q from set_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 383 of file mavlink_msg_set_home_position.h.

static uint8_t mavlink_msg_set_home_position_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Send a set_home_position 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)
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 target_system from set_home_position message
Returns
System ID.

Definition at line 313 of file mavlink_msg_set_home_position.h.

static float mavlink_msg_set_home_position_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from set_home_position message.

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

Definition at line 353 of file mavlink_msg_set_home_position.h.

static float mavlink_msg_set_home_position_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from set_home_position message.

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

Definition at line 363 of file mavlink_msg_set_home_position.h.

static float mavlink_msg_set_home_position_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from set_home_position message.

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

Definition at line 373 of file mavlink_msg_set_home_position.h.

static uint16_t mavlink_msg_set_home_position_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,
float  x,
float  y,
float  z,
const float *  q,
float  approach_x,
float  approach_y,
float  approach_z 
)
inlinestatic

Pack a set_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
target_systemSystem ID.
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 65 of file mavlink_msg_set_home_position.h.

static uint16_t mavlink_msg_set_home_position_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,
float  x,
float  y,
float  z,
const float *  q,
float  approach_x,
float  approach_y,
float  approach_z 
)
inlinestatic

Pack a set_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
target_systemSystem ID.
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 125 of file mavlink_msg_set_home_position.h.



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