Go to the source code of this file.
Classes | |
struct | __mavlink_altitude_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_ALTITUDE |
#define | MAVLINK_MSG_ID_141_CRC 47 |
#define | MAVLINK_MSG_ID_141_LEN 32 |
#define | MAVLINK_MSG_ID_ALTITUDE 141 |
#define | MAVLINK_MSG_ID_ALTITUDE_CRC 47 |
#define | MAVLINK_MSG_ID_ALTITUDE_LEN 32 |
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. More... | |
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. More... | |
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. More... | |
static float | mavlink_msg_altitude_get_altitude_amsl (const mavlink_message_t *msg) |
Get field altitude_amsl from altitude message. More... | |
static float | mavlink_msg_altitude_get_altitude_local (const mavlink_message_t *msg) |
Get field altitude_local from altitude message. More... | |
static float | mavlink_msg_altitude_get_altitude_monotonic (const mavlink_message_t *msg) |
Get field altitude_monotonic from altitude message. More... | |
static float | mavlink_msg_altitude_get_altitude_relative (const mavlink_message_t *msg) |
Get field altitude_relative from altitude message. More... | |
static float | mavlink_msg_altitude_get_altitude_terrain (const mavlink_message_t *msg) |
Get field altitude_terrain from altitude message. More... | |
static float | mavlink_msg_altitude_get_bottom_clearance (const mavlink_message_t *msg) |
Get field bottom_clearance from altitude message. More... | |
static uint64_t | mavlink_msg_altitude_get_time_usec (const mavlink_message_t *msg) |
Send a altitude message. More... | |
static uint16_t | mavlink_msg_altitude_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) |
Pack a altitude message. More... | |
static uint16_t | mavlink_msg_altitude_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, 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. More... | |
#define MAVLINK_MESSAGE_INFO_ALTITUDE |
Definition at line 24 of file mavlink_msg_altitude.h.
#define MAVLINK_MSG_ID_141_CRC 47 |
Definition at line 20 of file mavlink_msg_altitude.h.
#define MAVLINK_MSG_ID_141_LEN 32 |
Definition at line 17 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 47 |
Definition at line 19 of file mavlink_msg_altitude.h.
#define MAVLINK_MSG_ID_ALTITUDE_LEN 32 |
Definition at line 16 of file mavlink_msg_altitude.h.
typedef struct __mavlink_altitude_t mavlink_altitude_t |
|
inlinestatic |
Decode a altitude message into a struct.
msg | The message to decode |
altitude | C-struct to decode the message contents into |
Definition at line 340 of file mavlink_msg_altitude.h.
|
inlinestatic |
Encode a altitude struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
altitude | C-struct to read the message contents from |
Definition at line 147 of file mavlink_msg_altitude.h.
|
inlinestatic |
Encode a altitude struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
altitude | C-struct to read the message contents from |
Definition at line 161 of file mavlink_msg_altitude.h.
|
inlinestatic |
Get field altitude_amsl from altitude message.
Definition at line 289 of file mavlink_msg_altitude.h.
|
inlinestatic |
Get field altitude_local from altitude message.
Definition at line 299 of file mavlink_msg_altitude.h.
|
inlinestatic |
Get field altitude_monotonic from altitude message.
Definition at line 279 of file mavlink_msg_altitude.h.
|
inlinestatic |
Get field altitude_relative from altitude message.
Definition at line 309 of file mavlink_msg_altitude.h.
|
inlinestatic |
Get field altitude_terrain from altitude message.
Definition at line 319 of file mavlink_msg_altitude.h.
|
inlinestatic |
Get field bottom_clearance from altitude message.
Definition at line 329 of file mavlink_msg_altitude.h.
|
inlinestatic |
Send a altitude message.
chan | MAVLink channel to send the message |
time_usec | Timestamp (milliseconds since system boot) |
altitude_monotonic | 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. |
altitude_amsl | 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. |
altitude_local | 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. |
altitude_relative | This is the altitude above the home position. It resets on each change of the current home position. |
altitude_terrain | 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. |
bottom_clearance | 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. Get field time_usec from altitude message |
Definition at line 269 of file mavlink_msg_altitude.h.
|
inlinestatic |
Pack a altitude message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
time_usec | Timestamp (milliseconds since system boot) |
altitude_monotonic | 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. |
altitude_amsl | 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. |
altitude_local | 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. |
altitude_relative | This is the altitude above the home position. It resets on each change of the current home position. |
altitude_terrain | 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. |
bottom_clearance | 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 53 of file mavlink_msg_altitude.h.
|
inlinestatic |
Pack a altitude message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
time_usec | Timestamp (milliseconds since system boot) |
altitude_monotonic | 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. |
altitude_amsl | 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. |
altitude_local | 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. |
altitude_relative | This is the altitude above the home position. It resets on each change of the current home position. |
altitude_terrain | 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. |
bottom_clearance | 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 103 of file mavlink_msg_altitude.h.