Classes | Defines | Typedefs | Functions
mavlink_msg_altitude.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_altitude_t

Defines

#define MAVLINK_MESSAGE_INFO_ALTITUDE
#define MAVLINK_MSG_ID_141_CRC   148
#define MAVLINK_MSG_ID_141_LEN   24
#define MAVLINK_MSG_ID_ALTITUDE   141
#define MAVLINK_MSG_ID_ALTITUDE_CRC   148
#define MAVLINK_MSG_ID_ALTITUDE_LEN   24

Typedefs

typedef struct __mavlink_altitude_t mavlink_altitude_t

Functions

static void mavlink_msg_altitude_decode (const mavlink_message_t *msg, mavlink_altitude_t *altitude)
 Decode a altitude message into a struct.
static uint16_t mavlink_msg_altitude_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_altitude_t *altitude)
 Encode a altitude struct.
static uint16_t mavlink_msg_altitude_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_altitude_t *altitude)
 Encode a altitude struct on a channel.
static float mavlink_msg_altitude_get_altitude_amsl (const mavlink_message_t *msg)
 Get field altitude_amsl from altitude message.
static float mavlink_msg_altitude_get_altitude_local (const mavlink_message_t *msg)
 Get field altitude_local from altitude message.
static float mavlink_msg_altitude_get_altitude_monotonic (const mavlink_message_t *msg)
 Send a altitude message.
static float mavlink_msg_altitude_get_altitude_relative (const mavlink_message_t *msg)
 Get field altitude_relative from altitude message.
static float mavlink_msg_altitude_get_altitude_terrain (const mavlink_message_t *msg)
 Get field altitude_terrain from altitude message.
static float mavlink_msg_altitude_get_bottom_clearance (const mavlink_message_t *msg)
 Get field bottom_clearance from altitude message.
static uint16_t mavlink_msg_altitude_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
 Pack a altitude message.
static uint16_t mavlink_msg_altitude_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
 Pack a altitude message on a channel.

Define Documentation

Value:
{ \
        "ALTITUDE", \
        6, \
        {  { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_altitude_t, altitude_monotonic) }, \
         { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_altitude_t, altitude_amsl) }, \
         { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_local) }, \
         { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_relative) }, \
         { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_terrain) }, \
         { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, bottom_clearance) }, \
         } \
}

Definition at line 23 of file mavlink_msg_altitude.h.

#define MAVLINK_MSG_ID_141_CRC   148

Definition at line 19 of file mavlink_msg_altitude.h.

#define MAVLINK_MSG_ID_141_LEN   24

Definition at line 16 of file mavlink_msg_altitude.h.

#define MAVLINK_MSG_ID_ALTITUDE   141

Definition at line 3 of file mavlink_msg_altitude.h.

#define MAVLINK_MSG_ID_ALTITUDE_CRC   148

Definition at line 18 of file mavlink_msg_altitude.h.

#define MAVLINK_MSG_ID_ALTITUDE_LEN   24

Definition at line 15 of file mavlink_msg_altitude.h.


Typedef Documentation


Function Documentation

static void mavlink_msg_altitude_decode ( const mavlink_message_t msg,
mavlink_altitude_t altitude 
) [inline, static]

Decode a altitude message into a struct.

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

Definition at line 317 of file mavlink_msg_altitude.h.

static uint16_t mavlink_msg_altitude_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
const mavlink_altitude_t altitude 
) [inline, static]

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

Definition at line 139 of file mavlink_msg_altitude.h.

static uint16_t mavlink_msg_altitude_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
const mavlink_altitude_t altitude 
) [inline, static]

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

Definition at line 153 of file mavlink_msg_altitude.h.

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

Get field altitude_amsl from altitude message.

Returns:
This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.

Definition at line 266 of file mavlink_msg_altitude.h.

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

Get field altitude_local from altitude message.

Returns:
This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.

Definition at line 276 of file mavlink_msg_altitude.h.

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

Send a altitude message.

Parameters:
chanMAVLink channel to send the message
altitude_monotonicThis altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
altitude_amslThis altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
altitude_localThis is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
altitude_relativeThis is the altitude above the home position. It resets on each change of the current home position.
altitude_terrainThis is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bottom_clearanceThis is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. Get field altitude_monotonic from altitude message
Returns:
This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.

Definition at line 256 of file mavlink_msg_altitude.h.

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

Get field altitude_relative from altitude message.

Returns:
This is the altitude above the home position. It resets on each change of the current home position.

Definition at line 286 of file mavlink_msg_altitude.h.

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

Get field altitude_terrain from altitude message.

Returns:
This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.

Definition at line 296 of file mavlink_msg_altitude.h.

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

Get field bottom_clearance from altitude message.

Returns:
This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.

Definition at line 306 of file mavlink_msg_altitude.h.

static uint16_t mavlink_msg_altitude_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
float  altitude_monotonic,
float  altitude_amsl,
float  altitude_local,
float  altitude_relative,
float  altitude_terrain,
float  bottom_clearance 
) [inline, static]

Pack a altitude 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
altitude_monotonicThis altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
altitude_amslThis altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
altitude_localThis is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
altitude_relativeThis is the altitude above the home position. It resets on each change of the current home position.
altitude_terrainThis is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bottom_clearanceThis is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 50 of file mavlink_msg_altitude.h.

static uint16_t mavlink_msg_altitude_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
float  altitude_monotonic,
float  altitude_amsl,
float  altitude_local,
float  altitude_relative,
float  altitude_terrain,
float  bottom_clearance 
) [inline, static]

Pack a altitude 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
altitude_monotonicThis altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
altitude_amslThis altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
altitude_localThis is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
altitude_relativeThis is the altitude above the home position. It resets on each change of the current home position.
altitude_terrainThis is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bottom_clearanceThis is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 97 of file mavlink_msg_altitude.h.



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